mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Copter: reduce autotune min rate D to 0.002
This commit is contained in:
parent
450e9e83c3
commit
145a8ed128
@ -33,7 +33,7 @@
|
|||||||
#define AUTO_TUNE_SP_BACKOFF 0.75f // back off on the Stab P tune
|
#define AUTO_TUNE_SP_BACKOFF 0.75f // back off on the Stab P tune
|
||||||
#define AUTO_TUNE_PI_RATIO_FOR_TESTING 0.1f // I is set 10x smaller than P during testing
|
#define AUTO_TUNE_PI_RATIO_FOR_TESTING 0.1f // I is set 10x smaller than P during testing
|
||||||
#define AUTO_TUNE_RP_RATIO_FINAL 1.0f // I is set 1x P after testing
|
#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_MIN 0.002f // minimum Rate D value
|
||||||
#define AUTO_TUNE_RD_MAX 0.015f // maximum Rate D value
|
#define AUTO_TUNE_RD_MAX 0.015f // maximum Rate D value
|
||||||
#define AUTO_TUNE_RP_MIN 0.01f // 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_RP_MAX 0.25f // maximum Rate P value
|
||||||
|
Loading…
Reference in New Issue
Block a user