Copter: reduce default loiter PIDs

This commit is contained in:
Randy Mackay 2013-04-09 12:00:41 +09:00
parent 0ac3762bdd
commit 366616e32c

View File

@ -868,7 +868,7 @@
// Loiter position control gains // Loiter position control gains
// //
#ifndef LOITER_P #ifndef LOITER_P
# define LOITER_P 2.0f # define LOITER_P 1.0f
#endif #endif
#ifndef LOITER_I #ifndef LOITER_I
# define LOITER_I 0.0f # define LOITER_I 0.0f
@ -881,13 +881,13 @@
// Loiter rate control gains // Loiter rate control gains
// //
#ifndef LOITER_RATE_P #ifndef LOITER_RATE_P
# define LOITER_RATE_P 2.0f # define LOITER_RATE_P 1.0f
#endif #endif
#ifndef LOITER_RATE_I #ifndef LOITER_RATE_I
# define LOITER_RATE_I 1.0f # define LOITER_RATE_I 0.5f
#endif #endif
#ifndef LOITER_RATE_D #ifndef LOITER_RATE_D
# define LOITER_RATE_D 0.50f # define LOITER_RATE_D 0.25f
#endif #endif
#ifndef LOITER_RATE_IMAX #ifndef LOITER_RATE_IMAX
# define LOITER_RATE_IMAX 30 // degrees # define LOITER_RATE_IMAX 30 // degrees