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:
rmackay9 2012-12-09 18:08:45 +09:00
parent 6cdcf5e737
commit 97153c32d0
1 changed files with 4 additions and 4 deletions

View File

@ -724,10 +724,10 @@
# define MAX_INPUT_PITCH_ANGLE 4500
#endif
#ifndef RATE_ROLL_P
# define RATE_ROLL_P 0.175
# define RATE_ROLL_P 0.150
#endif
#ifndef RATE_ROLL_I
# define RATE_ROLL_I 0.010
# define RATE_ROLL_I 0.100
#endif
#ifndef RATE_ROLL_D
# define RATE_ROLL_D 0.004
@ -737,10 +737,10 @@
#endif
#ifndef RATE_PITCH_P
# define RATE_PITCH_P 0.175
# define RATE_PITCH_P 0.150
#endif
#ifndef RATE_PITCH_I
# define RATE_PITCH_I 0.010
# define RATE_PITCH_I 0.100
#endif
#ifndef RATE_PITCH_D
# define RATE_PITCH_D 0.004