mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
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:
parent
228ad2198f
commit
9b2956b377
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user