mirror of https://github.com/ArduPilot/ardupilot
Added OPtion for non-rate based loiter
This commit is contained in:
parent
9a2be4701f
commit
bab1faf644
|
@ -663,6 +663,10 @@
|
|||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Loiter Navigation control gains
|
||||
//
|
||||
#ifndef LOITER_RATE
|
||||
# define LOITER_RATE 0
|
||||
#endif
|
||||
|
||||
#ifndef LOITER_RATE_P
|
||||
# define LOITER_RATE_P 3.5 //
|
||||
#endif
|
||||
|
@ -670,7 +674,7 @@
|
|||
# define LOITER_RATE_I 0.2 // Wind control
|
||||
#endif
|
||||
#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
|
||||
#ifndef LOITER_RATE_IMAX
|
||||
# define LOITER_RATE_IMAX 30 // degrees
|
||||
|
|
Loading…
Reference in New Issue