Copter: adjust autotune P and D min and max

This commit is contained in:
Randy Mackay 2013-10-17 10:20:16 +09:00
parent 94e707094a
commit 5ac3bf4915

View File

@ -33,10 +33,10 @@
#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_RP_RATIO_FINAL 1.0f // I is set 1x P after testing
#define AUTO_TUNE_RD_MIN 0.0f // minimum Rate D value
#define AUTO_TUNE_RD_MAX 0.1f // maximum Rate D value
#define AUTO_TUNE_RP_MIN 0.02f // minimum Rate P value
#define AUTO_TUNE_RP_MAX 1.0f // maximum Rate P value
#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.05f // minimum Rate P value
#define AUTO_TUNE_RP_MAX 0.25f // maximum Rate P value
#define AUTO_TUNE_SP_MIN 1.0f // minimum Stab 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