mirror of https://github.com/ArduPilot/ardupilot
Copter: reduce default loiter PIDs
This commit is contained in:
parent
0ac3762bdd
commit
366616e32c
|
@ -868,7 +868,7 @@
|
|||
// Loiter position control gains
|
||||
//
|
||||
#ifndef LOITER_P
|
||||
# define LOITER_P 2.0f
|
||||
# define LOITER_P 1.0f
|
||||
#endif
|
||||
#ifndef LOITER_I
|
||||
# define LOITER_I 0.0f
|
||||
|
@ -881,13 +881,13 @@
|
|||
// Loiter rate control gains
|
||||
//
|
||||
#ifndef LOITER_RATE_P
|
||||
# define LOITER_RATE_P 2.0f
|
||||
# define LOITER_RATE_P 1.0f
|
||||
#endif
|
||||
#ifndef LOITER_RATE_I
|
||||
# define LOITER_RATE_I 1.0f
|
||||
# define LOITER_RATE_I 0.5f
|
||||
#endif
|
||||
#ifndef LOITER_RATE_D
|
||||
# define LOITER_RATE_D 0.50f
|
||||
# define LOITER_RATE_D 0.25f
|
||||
#endif
|
||||
#ifndef LOITER_RATE_IMAX
|
||||
# define LOITER_RATE_IMAX 30 // degrees
|
||||
|
|
Loading…
Reference in New Issue