mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Plane: allow for AUTOTUNE_LEVEL==0
This commit is contained in:
parent
97f88f67f6
commit
96059a6387
@ -38,8 +38,8 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
|
||||
// @Param: AUTOTUNE_LEVEL
|
||||
// @DisplayName: Autotune level
|
||||
// @Description: Level of aggressiveness of pitch and roll PID gains. Lower values result in a 'softer' tune. Level 6 recommended for most planes.
|
||||
// @Range: 1 10
|
||||
// @Description: Level of aggressiveness of pitch and roll PID gains. Lower values result in a 'softer' tune. Level 6 recommended for most planes. A value of 0 means to keep the current values of RMAX and TCONST for the controllers, tuning only the PID values
|
||||
// @Range: 0 10
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
ASCALAR(autotune_level, "AUTOTUNE_LEVEL", 6),
|
||||
|
Loading…
Reference in New Issue
Block a user