diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 698cdd6d75..b309f5d6fa 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -622,20 +622,23 @@ # define LOITER_P 1.5 // was .25 in previous #endif #ifndef LOITER_I -# define LOITER_I 0.04 // Wind control +# define LOITER_I 0.09 // Wind control #endif #ifndef LOITER_IMAX # define LOITER_IMAX 30 // degreesĀ° #endif +#ifndef LOITER_D +# define LOITER_D 2.2 // rate control +#endif ////////////////////////////////////////////////////////////////////////////// // WP Navigation control gains // #ifndef NAV_P -# define NAV_P 2.2 // 3 was causing rapid oscillations in Loiter +# define NAV_P 3.0 // 3 was causing rapid oscillations in Loiter #endif #ifndef NAV_I -# define NAV_I 0.15 // used in traverals +# define NAV_I 0 // #endif #ifndef NAV_IMAX # define NAV_IMAX 30 // degrees @@ -645,6 +648,10 @@ # define WAYPOINT_SPEED_MAX 600 // for 6m/s error = 13mph #endif +#ifndef WAYPOINT_SPEED_MIN +# define WAYPOINT_SPEED_MIN 100 // for 6m/s error = 13mph +#endif + ////////////////////////////////////////////////////////////////////////////// // Throttle control gains