mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 21:05:35 +03:00
The yaw_p_limit minimum is now set to 100 to prevent misconfigurations.
Maximum value of 500 is now removing the limit (same as for yaw_jump_prevention_limit) Moving defines for PID controllers to headerfiles. Some general code cleanup. Documentation update
This commit is contained in:
parent
3037a91b06
commit
42218f1ea5
7 changed files with 18 additions and 14 deletions
|
@ -359,7 +359,7 @@ const clivalue_t valueTable[] = {
|
|||
{ "vbat_max_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmaxcellvoltage, 10, 50 },
|
||||
{ "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmincellvoltage, 10, 50 },
|
||||
{ "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatwarningcellvoltage, 10, 50 },
|
||||
{ "current_meter_scale", VAR_INT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterScale, -10000, 10000 },
|
||||
{ "current_meter_scale", VAR_INT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterScale, -10000, 10000 },
|
||||
{ "current_meter_offset", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterOffset, 0, 3300 },
|
||||
{ "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.multiwiiCurrentMeterOutput, 0, 1 },
|
||||
{ "current_meter_type", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterType, 0, CURRENT_SENSOR_MAX },
|
||||
|
@ -391,7 +391,7 @@ const clivalue_t valueTable[] = {
|
|||
|
||||
{ "pid_at_min_throttle", VAR_UINT8 | MASTER_VALUE, &masterConfig.mixerConfig.pid_at_min_throttle, 0, 1 },
|
||||
{ "yaw_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_direction, -1, 1 },
|
||||
{ "yaw_jump_prevention_limit", VAR_UINT16 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_jump_prevention_limit, 80, 500 },
|
||||
{ "yaw_jump_prevention_limit", VAR_UINT16 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_jump_prevention_limit, YAW_JUMP_PREVENTION_LIMIT_LOW, YAW_JUMP_PREVENTION_LIMIT_HIGH },
|
||||
#ifdef USE_SERVOS
|
||||
{ "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE, &masterConfig.mixerConfig.tri_unarmed_servo, 0, 1 },
|
||||
{ "servo_lowpass_freq", VAR_INT16 | MASTER_VALUE, &masterConfig.mixerConfig.servo_lowpass_freq, 10, 400},
|
||||
|
@ -476,7 +476,7 @@ const clivalue_t valueTable[] = {
|
|||
{ "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], 0, 200 },
|
||||
{ "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], 0, 200 },
|
||||
|
||||
{ "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, 0, 500 },
|
||||
{ "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX },
|
||||
|
||||
#ifdef BLACKBOX
|
||||
{ "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, 1, 32 },
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue