mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
ArduCopter: reduce Rate Roll/Pitch P to 0.150 (was 0.175) and increase I to 0.1 (was 0.01)
This commit is contained in:
parent
56ceb230cb
commit
cfe2507c0b
@ -724,10 +724,10 @@
|
|||||||
# define MAX_INPUT_PITCH_ANGLE 4500
|
# define MAX_INPUT_PITCH_ANGLE 4500
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_ROLL_P
|
#ifndef RATE_ROLL_P
|
||||||
# define RATE_ROLL_P 0.175
|
# define RATE_ROLL_P 0.150
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_ROLL_I
|
#ifndef RATE_ROLL_I
|
||||||
# define RATE_ROLL_I 0.010
|
# define RATE_ROLL_I 0.100
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_ROLL_D
|
#ifndef RATE_ROLL_D
|
||||||
# define RATE_ROLL_D 0.004
|
# define RATE_ROLL_D 0.004
|
||||||
@ -737,10 +737,10 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef RATE_PITCH_P
|
#ifndef RATE_PITCH_P
|
||||||
# define RATE_PITCH_P 0.175
|
# define RATE_PITCH_P 0.150
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_PITCH_I
|
#ifndef RATE_PITCH_I
|
||||||
# define RATE_PITCH_I 0.010
|
# define RATE_PITCH_I 0.100
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_PITCH_D
|
#ifndef RATE_PITCH_D
|
||||||
# define RATE_PITCH_D 0.004
|
# define RATE_PITCH_D 0.004
|
||||||
|
Loading…
Reference in New Issue
Block a user