ArduCopter: reduced Rate Roll and Pitch PID values

RATE_ROLL_P, RATE_PITCH_P reduced to 0.165 (was 0.185)
RATE_ROLL_D, RATE_PITCH_D reduced to 0.004 (was 0.008)
This commit is contained in:
rmackay9 2012-08-26 10:45:45 +09:00
parent b9fb1750d5
commit ccc659e8a9
1 changed files with 4 additions and 4 deletions

View File

@ -698,26 +698,26 @@
// Stabilize Rate Control // Stabilize Rate Control
// //
#ifndef RATE_ROLL_P #ifndef RATE_ROLL_P
# define RATE_ROLL_P 0.185 # define RATE_ROLL_P 0.165
#endif #endif
#ifndef RATE_ROLL_I #ifndef RATE_ROLL_I
# define RATE_ROLL_I 0.0 # define RATE_ROLL_I 0.0
#endif #endif
#ifndef RATE_ROLL_D #ifndef RATE_ROLL_D
# define RATE_ROLL_D 0.008 # define RATE_ROLL_D 0.004
#endif #endif
#ifndef RATE_ROLL_IMAX #ifndef RATE_ROLL_IMAX
# define RATE_ROLL_IMAX 5.0 // degrees # define RATE_ROLL_IMAX 5.0 // degrees
#endif #endif
#ifndef RATE_PITCH_P #ifndef RATE_PITCH_P
# define RATE_PITCH_P 0.185 # define RATE_PITCH_P 0.165
#endif #endif
#ifndef RATE_PITCH_I #ifndef RATE_PITCH_I
# define RATE_PITCH_I 0.0 # define RATE_PITCH_I 0.0
#endif #endif
#ifndef RATE_PITCH_D #ifndef RATE_PITCH_D
# define RATE_PITCH_D 0.008 # define RATE_PITCH_D 0.004
#endif #endif
#ifndef RATE_PITCH_IMAX #ifndef RATE_PITCH_IMAX
# define RATE_PITCH_IMAX 5.0 // degrees # define RATE_PITCH_IMAX 5.0 // degrees