ArduCopter: set default rate roll and pitch I terms to 0.010, and rate yaw to 0.015

Updated after discussing with Marco
This commit is contained in:
rmackay9 2012-10-11 17:25:01 +09:00
parent 35fa50234f
commit 03933df5b7
1 changed files with 3 additions and 3 deletions

View File

@ -699,7 +699,7 @@
# define RATE_ROLL_P 0.175 # define RATE_ROLL_P 0.175
#endif #endif
#ifndef RATE_ROLL_I #ifndef RATE_ROLL_I
# define RATE_ROLL_I 0.02 # define RATE_ROLL_I 0.010
#endif #endif
#ifndef RATE_ROLL_D #ifndef RATE_ROLL_D
# define RATE_ROLL_D 0.004 # define RATE_ROLL_D 0.004
@ -712,7 +712,7 @@
# define RATE_PITCH_P 0.175 # define RATE_PITCH_P 0.175
#endif #endif
#ifndef RATE_PITCH_I #ifndef RATE_PITCH_I
# define RATE_PITCH_I 0.02 # define RATE_PITCH_I 0.010
#endif #endif
#ifndef RATE_PITCH_D #ifndef RATE_PITCH_D
# define RATE_PITCH_D 0.004 # define RATE_PITCH_D 0.004
@ -725,7 +725,7 @@
# define RATE_YAW_P .25 # define RATE_YAW_P .25
#endif #endif
#ifndef RATE_YAW_I #ifndef RATE_YAW_I
# define RATE_YAW_I 0.02 # define RATE_YAW_I 0.015
#endif #endif
#ifndef RATE_YAW_D #ifndef RATE_YAW_D
# define RATE_YAW_D 0.000 # define RATE_YAW_D 0.000