ArduCopter: increase default Loiter Rate P to 5.0

This commit is contained in:
rmackay9 2012-09-25 12:19:44 +09:00
parent bbec662483
commit a71aa21514

View File

@ -768,7 +768,7 @@
// Loiter Navigation control gains
//
#ifndef LOITER_RATE_P
# define LOITER_RATE_P 2.4 //
# define LOITER_RATE_P 5.0 //
#endif
#ifndef LOITER_RATE_I
# define LOITER_RATE_I 0.08 // Wind control