Added OPtion for non-rate based loiter

This commit is contained in:
Jason Short 2012-02-26 11:33:02 -08:00
parent 9a2be4701f
commit bab1faf644
1 changed files with 5 additions and 1 deletions

View File

@ -663,6 +663,10 @@
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Loiter Navigation control gains // Loiter Navigation control gains
// //
#ifndef LOITER_RATE
# define LOITER_RATE 0
#endif
#ifndef LOITER_RATE_P #ifndef LOITER_RATE_P
# define LOITER_RATE_P 3.5 // # define LOITER_RATE_P 3.5 //
#endif #endif
@ -670,7 +674,7 @@
# define LOITER_RATE_I 0.2 // Wind control # define LOITER_RATE_I 0.2 // Wind control
#endif #endif
#ifndef LOITER_RATE_D #ifndef LOITER_RATE_D
# define LOITER_RATE_D 0.00 // # define LOITER_RATE_D 0.0 // try 2 or 3 for LOITER_RATE 1
#endif #endif
#ifndef LOITER_RATE_IMAX #ifndef LOITER_RATE_IMAX
# define LOITER_RATE_IMAX 30 // degrees # define LOITER_RATE_IMAX 30 // degrees