From 7e1e1f84b35a29f9601027b4c7601dce88b8f6d8 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Wed, 28 Dec 2011 22:37:00 -0800 Subject: [PATCH] updated Loiter PIDs --- ArduCopter/config.h | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 0132e0a270..a20bb1d538 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -370,6 +370,11 @@ #ifndef MINIMUM_THROTTLE # define MINIMUM_THROTTLE 130 #endif +#ifndef MAXIMUM_THROTTLE +# define MAXIMUM_THROTTLE 1000 +#endif + + ////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////// @@ -600,7 +605,7 @@ # define LOITER_P .3 // #endif #ifndef LOITER_I -# define LOITER_I 0.01 // +# define LOITER_I 0.05 // Wind control #endif #ifndef LOITER_IMAX # define LOITER_IMAX 30 // degreesĀ° @@ -610,7 +615,7 @@ # define NAV_P 3.0 // #endif #ifndef NAV_I -# define NAV_I 0.14 // Lowerd from .25 - saw lots of overshoot. +# define NAV_I 0.15 // Lowerd from .25 - saw lots of overshoot. #endif #ifndef NAV_IMAX # define NAV_IMAX 30 // degrees