From ce990f3050632369f02b396420d2d03b7d5a51f8 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Thu, 29 Dec 2011 10:23:59 -0800 Subject: [PATCH] Upped Yaw speed to deal with performance complaints Added new Stabilize D term default of .25 --- ArduCopter/config.h | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index a20bb1d538..10f1921e52 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -507,6 +507,10 @@ #endif +#ifndef STABILIZE_D +# define STABILIZE_D .25 +#endif + // Jasons default values that are good for smaller payload motors. #ifndef STABILIZE_ROLL_P # define STABILIZE_ROLL_P 4.6 @@ -578,7 +582,7 @@ // YAW Control // #ifndef STABILIZE_YAW_P -# define STABILIZE_YAW_P 7 // increase for more aggressive Yaw Hold, decrease if it's bouncy +# define STABILIZE_YAW_P 10 // increase for more aggressive Yaw Hold, decrease if it's bouncy #endif #ifndef STABILIZE_YAW_I # define STABILIZE_YAW_I 0.01 // set to .0001 to try and get over user's steady state error caused by poor balance