From 145a8ed128cf1362ea87031fa248ec61fb9e04b6 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 9 Dec 2013 14:17:31 +0900 Subject: [PATCH] Copter: reduce autotune min rate D to 0.002 --- ArduCopter/auto_tune.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/auto_tune.pde b/ArduCopter/auto_tune.pde index 734af8a275..966099f5c9 100644 --- a/ArduCopter/auto_tune.pde +++ b/ArduCopter/auto_tune.pde @@ -33,7 +33,7 @@ #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.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_RP_MIN 0.01f // minimum Rate P value #define AUTO_TUNE_RP_MAX 0.25f // maximum Rate P value