diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.h b/libraries/AC_AttitudeControl/AC_AttitudeControl.h index 4e70a1a289..c259051c41 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.h @@ -21,8 +21,8 @@ #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 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 90000 // 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 +#define AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT 126000 // default maximum acceleration for roll/pitch axis in centi-degrees/sec/sec +#define AC_ATTITUDE_CONTROL_ACCEL_Y_MAX_DEFAULT 36000 // default maximum acceleration for yaw axis in centi-degrees/sec/sec #define AC_ATTITUDE_RATE_CONTROLLER_TIMEOUT 1.0f // body-frame rate controller timeout in seconds #define AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX 5000.0f // body-frame rate controller maximum output (for roll-pitch axis)