mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 21:35:44 +03:00
added max_angle_inclination to CLI to configure (default) 50 degree max inclination. configurable between 10 and 90 (100..900 in cli)
This commit is contained in:
parent
9d421b4a67
commit
202fc17608
4 changed files with 7 additions and 4 deletions
|
@ -145,6 +145,7 @@ const clivalue_t valueTable[] = {
|
|||
{ "align_board_yaw", VAR_INT16, &mcfg.board_align_yaw, -180, 360 },
|
||||
{ "yaw_control_direction", VAR_INT8, &mcfg.yaw_control_direction, -1, 1 },
|
||||
{ "acc_hardware", VAR_UINT8, &mcfg.acc_hardware, 0, 5 },
|
||||
{ "max_angle_inclination", VAR_UINT16, &mcfg.max_angle_inclination, 100, 900 },
|
||||
{ "moron_threshold", VAR_UINT8, &mcfg.moron_threshold, 0, 128 },
|
||||
{ "gyro_lpf", VAR_UINT16, &mcfg.gyro_lpf, 0, 256 },
|
||||
{ "gyro_cmpf_factor", VAR_UINT16, &mcfg.gyro_cmpf_factor, 100, 1000 },
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue