diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 3435cec68c..78376add1c 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -578,7 +578,7 @@ # define STABILIZE_ROLL_P 4.5 #endif #ifndef STABILIZE_ROLL_I -# define STABILIZE_ROLL_I 0.0 +# define STABILIZE_ROLL_I 0.1 #endif #ifndef STABILIZE_ROLL_IMAX # define STABILIZE_ROLL_IMAX 40 // degrees @@ -588,7 +588,7 @@ # define STABILIZE_PITCH_P 4.5 #endif #ifndef STABILIZE_PITCH_I -# define STABILIZE_PITCH_I 0.0 +# define STABILIZE_PITCH_I 0.1 #endif #ifndef STABILIZE_PITCH_IMAX # define STABILIZE_PITCH_IMAX 40 // degrees @@ -615,7 +615,7 @@ # define RATE_ROLL_I 0.0 #endif #ifndef RATE_ROLL_D -# define RATE_ROLL_D 0.002 +# define RATE_ROLL_D 0.000 //.002 #endif #ifndef RATE_ROLL_IMAX # define RATE_ROLL_IMAX 5 // degrees @@ -628,7 +628,7 @@ # define RATE_PITCH_I 0.0 #endif #ifndef RATE_PITCH_D -# define RATE_PITCH_D 0.002 +# define RATE_PITCH_D 0.00 #endif #ifndef RATE_PITCH_IMAX # define RATE_PITCH_IMAX 5 // degrees @@ -641,7 +641,7 @@ # define RATE_YAW_I 0.0 #endif #ifndef RATE_YAW_D -# define RATE_YAW_D .000 +# define RATE_YAW_D 0.000 #endif #ifndef RATE_YAW_IMAX # define RATE_YAW_IMAX 50 // degrees @@ -649,18 +649,18 @@ #ifndef STABILIZE_D -# define STABILIZE_D 0.1 +# define STABILIZE_D 0.15 #endif #ifndef STABILIZE_D_SCHEDULE -# define STABILIZE_D_SCHEDULE 0.0 +# define STABILIZE_D_SCHEDULE 0.5 #endif ////////////////////////////////////////////////////////////////////////////// // Loiter control gains // #ifndef LOITER_P -# define LOITER_P .8 +# define LOITER_P .4 #endif #ifndef LOITER_I # define LOITER_I 0.0 @@ -677,10 +677,10 @@ #endif #ifndef LOITER_RATE_P -# define LOITER_RATE_P 3.5 // +# define LOITER_RATE_P 3.0 // #endif #ifndef LOITER_RATE_I -# define LOITER_RATE_I 0.2 // Wind control +# define LOITER_RATE_I 0.25 // Wind control #endif #ifndef LOITER_RATE_D # define LOITER_RATE_D 0.0 // try 2 or 3 for LOITER_RATE 1 @@ -693,10 +693,10 @@ // WP Navigation control gains // #ifndef NAV_P -# define NAV_P 3.5 // +# define NAV_P 3.0 // #endif #ifndef NAV_I -# define NAV_I 0.2 // Wind control +# define NAV_I 0.25 // Wind control #endif #ifndef NAV_D # define NAV_D 0.00 // @@ -727,10 +727,10 @@ #endif #ifndef ALT_HOLD_P -# define ALT_HOLD_P 0.4 // +# define ALT_HOLD_P 0.2 // #endif #ifndef ALT_HOLD_I -# define ALT_HOLD_I 0.04 +# define ALT_HOLD_I 0.015 #endif #ifndef ALT_HOLD_IMAX # define ALT_HOLD_IMAX 300 @@ -738,7 +738,7 @@ // RATE control #ifndef THROTTLE_P -# define THROTTLE_P 0.35 // +# define THROTTLE_P 0.45 // #endif #ifndef THROTTLE_I # define THROTTLE_I 0.0 //