mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: loiter rate IMAX to 4m/s/s and D to zero
This commit is contained in:
parent
b8974dec99
commit
0663da7c9e
@ -887,10 +887,10 @@
|
||||
# define LOITER_RATE_I 0.5f
|
||||
#endif
|
||||
#ifndef LOITER_RATE_D
|
||||
# define LOITER_RATE_D 0.25f
|
||||
# define LOITER_RATE_D 0.0f
|
||||
#endif
|
||||
#ifndef LOITER_RATE_IMAX
|
||||
# define LOITER_RATE_IMAX 30 // degrees
|
||||
# define LOITER_RATE_IMAX 4 // maximum acceleration from I term build-up in m/s/s
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
Loading…
Reference in New Issue
Block a user