diff --git a/ArduCopter/auto_tune.pde b/ArduCopter/auto_tune.pde index 37eb8d14e8..734af8a275 100644 --- a/ArduCopter/auto_tune.pde +++ b/ArduCopter/auto_tune.pde @@ -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