mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
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:
parent
94d16d426f
commit
a5feda6b1f
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user