Copter: revert Loiter Pos P to 1.0 (was 0.8)

This commit is contained in:
Randy Mackay 2013-07-11 12:19:45 +09:00
parent 42a837033e
commit 0856e01341

View File

@ -873,7 +873,7 @@
// Loiter position control gains
//
#ifndef LOITER_P
# define LOITER_P 0.8f
# define LOITER_P 1.0f
#endif
#ifndef LOITER_I
# define LOITER_I 0.0f