mirror of https://github.com/ArduPilot/ardupilot
AC_AttControl: increase max angle overshoot to 30deg
This commit is contained in:
parent
eb084f7c58
commit
784a4ce51a
|
@ -32,7 +32,7 @@
|
|||
#define AC_ATTITUDE_RATE_STAB_ROLL_OVERSHOOT_ANGLE_MAX 3000.0f // earth-frame rate stabilize controller's maximum overshoot angle
|
||||
#define AC_ATTITUDE_RATE_STAB_PITCH_OVERSHOOT_ANGLE_MAX 3000.0f // earth-frame rate stabilize controller's maximum overshoot angle
|
||||
#define AC_ATTITUDE_RATE_STAB_YAW_OVERSHOOT_ANGLE_MAX 1000.0f // earth-frame rate stabilize controller's maximum overshoot angle
|
||||
#define AC_ATTITUDE_RATE_STAB_ACRO_OVERSHOOT_ANGLE_MAX 1000.0f // earth-frame rate stabilize controller's maximum overshoot angle
|
||||
#define AC_ATTITUDE_RATE_STAB_ACRO_OVERSHOOT_ANGLE_MAX 3000.0f // earth-frame rate stabilize controller's maximum overshoot angle
|
||||
|
||||
#define AC_ATTITUDE_100HZ_DT 0.0100f // delta time in seconds for 100hz update rate
|
||||
#define AC_ATTITUDE_400HZ_DT 0.0025f // delta time in seconds for 400hz update rate
|
||||
|
|
Loading…
Reference in New Issue