ArduCopter: increase throttle rate P to 6.0 (was 1.0) and alt hold P to 2.0 (was 1.0)

This commit is contained in:
rmackay9 2012-12-31 14:42:13 +09:00 committed by Andrew Tridgell
parent 228ad2198f
commit 9b2956b377

View File

@ -901,7 +901,7 @@
#endif
#ifndef ALT_HOLD_P
# define ALT_HOLD_P 1.0
# define ALT_HOLD_P 2.0
#endif
#ifndef ALT_HOLD_I
# define ALT_HOLD_I 0.0
@ -912,7 +912,7 @@
// RATE control
#ifndef THROTTLE_P
# define THROTTLE_P 1.0
# define THROTTLE_P 6.0
#endif
#ifndef THROTTLE_I
# define THROTTLE_I 0.0