mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
Copter: reduce autotune min rate P to 0.01 (was 0.02)
This commit is contained in:
parent
222ad82b5f
commit
eb938c6ac0
@ -35,7 +35,7 @@
|
||||
#define AUTO_TUNE_RP_RATIO_FINAL 1.0f // I is set 1x P after testing
|
||||
#define AUTO_TUNE_RD_MIN 0.004f // minimum Rate D value
|
||||
#define AUTO_TUNE_RD_MAX 0.015f // maximum Rate D value
|
||||
#define AUTO_TUNE_RP_MIN 0.02f // minimum Rate P value
|
||||
#define AUTO_TUNE_RP_MIN 0.01f // minimum Rate P value
|
||||
#define AUTO_TUNE_RP_MAX 0.25f // maximum Rate P value
|
||||
#define AUTO_TUNE_SP_MAX 15.0f // maximum Stab P value
|
||||
#define AUTO_TUNE_SUCCESS_COUNT 4 // how many successful iterations we need to freeze at current gains
|
||||
|
Loading…
Reference in New Issue
Block a user