Skip to content
Snippets Groups Projects
Commit a5feda6b authored by rmackay9's avatar rmackay9
Browse files

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

Updated after discussing with Marco
parent 94d16d42
No related branches found
No related tags found
No related merge requests found
......@@ -699,7 +699,7 @@
# define RATE_ROLL_P 0.175
#endif
#ifndef RATE_ROLL_I
# define RATE_ROLL_I 0.02
# define RATE_ROLL_I 0.010
#endif
#ifndef RATE_ROLL_D
# define RATE_ROLL_D 0.004
......@@ -712,7 +712,7 @@
# define RATE_PITCH_P 0.175
#endif
#ifndef RATE_PITCH_I
# define RATE_PITCH_I 0.02
# define RATE_PITCH_I 0.010
#endif
#ifndef RATE_PITCH_D
# define RATE_PITCH_D 0.004
......@@ -725,7 +725,7 @@
# define RATE_YAW_P .25
#endif
#ifndef RATE_YAW_I
# define RATE_YAW_I 0.02
# define RATE_YAW_I 0.015
#endif
#ifndef RATE_YAW_D
# define RATE_YAW_D 0.000
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment