mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AC_AttControl: 45deg/sec yaw rate for Auto, RTL
This commit is contained in:
parent
d27ca53a9d
commit
3ad635feeb
@ -20,7 +20,7 @@
|
||||
#define AC_ATTITUDE_CONTROL_DEGX100 5729.57795f // constant to convert from radians to centi-degrees
|
||||
#define AC_ATTITUDE_CONTROL_RATE_RP_MAX_DEFAULT 18000 // maximum rotation rate in roll/pitch axis requested by angle controller used in stabilize, loiter, rtl, auto flight modes
|
||||
#define AC_ATTITUDE_CONTROL_RATE_Y_MAX_DEFAULT 18000 // maximum rotation rate on yaw axis requested by angle controller used in stabilize, loiter, rtl, auto flight modes
|
||||
#define AC_ATTITUDE_CONTROL_SLEW_YAW_DEFAULT 6000 // default yaw slew rate in centi-degrees/sec (i.e. maximum yaw target change in 1second)
|
||||
#define AC_ATTITUDE_CONTROL_SLEW_YAW_DEFAULT 1000 // constraint on yaw angle error in degrees. This should lead to maximum turn rate of 10deg/sed * Stab Rate P so by default will be 45deg/sec.
|
||||
#define AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT 54000 // default maximum acceleration for roll/pitch axis in centi-degrees/sec/sec
|
||||
#define AC_ATTITUDE_CONTROL_ACCEL_Y_MAX_DEFAULT 18000 // default maximum acceleration for yaw axis in centi-degrees/sec/sec
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user