updated Loiter PIDs

This commit is contained in:
Jason Short 2011-12-28 22:37:00 -08:00
parent a29aa020ff
commit 7e1e1f84b3

View File

@ -370,6 +370,11 @@
#ifndef MINIMUM_THROTTLE #ifndef MINIMUM_THROTTLE
# define MINIMUM_THROTTLE 130 # define MINIMUM_THROTTLE 130
#endif #endif
#ifndef MAXIMUM_THROTTLE
# define MAXIMUM_THROTTLE 1000
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
@ -600,7 +605,7 @@
# define LOITER_P .3 // # define LOITER_P .3 //
#endif #endif
#ifndef LOITER_I #ifndef LOITER_I
# define LOITER_I 0.01 // # define LOITER_I 0.05 // Wind control
#endif #endif
#ifndef LOITER_IMAX #ifndef LOITER_IMAX
# define LOITER_IMAX 30 // degrees° # define LOITER_IMAX 30 // degrees°
@ -610,7 +615,7 @@
# define NAV_P 3.0 // # define NAV_P 3.0 //
#endif #endif
#ifndef NAV_I #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 #endif
#ifndef NAV_IMAX #ifndef NAV_IMAX
# define NAV_IMAX 30 // degrees # define NAV_IMAX 30 // degrees