Browse Source

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)
mission-4.1.18
rmackay9 13 years ago
parent
commit
b4b394e67e
  1. 8
      ArduCopter/config.h

8
ArduCopter/config.h

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

Loading…
Cancel
Save