Copter: increase LOITER_RATE_IMAX to 1000
This allows us to load up the I term with the vehicle's current acceleration during mode transitions pair programmed with Randy
This commit is contained in:
parent
fb2be07b44
commit
ff1a58e078
@ -629,7 +629,7 @@
|
||||
# define LOITER_RATE_D 0.0f
|
||||
#endif
|
||||
#ifndef LOITER_RATE_IMAX
|
||||
# define LOITER_RATE_IMAX 400 // maximum acceleration from I term build-up in cm/s/s
|
||||
# define LOITER_RATE_IMAX 1000 // maximum acceleration from I term build-up in cm/s/s
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
Loading…
Reference in New Issue
Block a user