From b3e629cfbf7962492b45f5aceca4065474b034ac Mon Sep 17 00:00:00 2001 From: jasonshort Date: Sun, 17 Jul 2011 19:14:23 +0000 Subject: [PATCH] 2.0.37 Added rate of change limit for noisy Sonars. converted to static functions - Tridge New Throttle PIDs from Jack git-svn-id: https://arducopter.googlecode.com/svn/trunk@2904 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArduCopterMega/config.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopterMega/config.h b/ArduCopterMega/config.h index 6eb79b549d..f8bcbb8ce0 100644 --- a/ArduCopterMega/config.h +++ b/ArduCopterMega/config.h @@ -399,13 +399,13 @@ // Throttle control gains // #ifndef THROTTLE_P -# define THROTTLE_P 0.25 // trying a lower val +# define THROTTLE_P 0.3 // trying a lower val #endif #ifndef THROTTLE_I -# define THROTTLE_I 0.01 //with 4m error, 12.5s windup +# define THROTTLE_I 0.04 //with 4m error, 12.5s windup #endif #ifndef THROTTLE_D -# define THROTTLE_D 0.25 // upped with filter +# define THROTTLE_D 0.35 // upped with filter #endif #ifndef THROTTLE_IMAX # define THROTTLE_IMAX 30