From 5876a2fe47dff81f8a90e92952f4de8af2bf0c89 Mon Sep 17 00:00:00 2001 From: Randy Mackay <rmackay9@yahoo.com> Date: Fri, 4 Apr 2014 17:47:11 +0900 Subject: [PATCH] AC_AttControl: increase default rp accel to 900deg/s/s --- libraries/AC_AttitudeControl/AC_AttitudeControl.cpp | 3 +-- libraries/AC_AttitudeControl/AC_AttitudeControl.h | 2 +- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp index a460f5378..7fb570010 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp @@ -39,8 +39,7 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] PROGMEM = { // @DisplayName: Acceleration Max for Roll/Pitch // @Description: Maximum acceleration in roll/pitch axis // @Units: Centi-Degrees/Sec/Sec - // @Range: 20000 100000 - // @Increment: 100 + // @Values: 36000:Very Soft, 54000:Soft, 90000:Medium, 126000:Crisp, 162000:Very Crisp // @User: Advanced AP_GROUPINFO("ACCEL_RP_MAX", 3, AC_AttitudeControl, _accel_rp_max, AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT), diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.h b/libraries/AC_AttitudeControl/AC_AttitudeControl.h index 21ad6df0d..85f94ff8e 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.h @@ -21,7 +21,7 @@ #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 54000 // default maximum acceleration for roll/pitch axis in centi-degrees/sec/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_RATE_CONTROLLER_TIMEOUT 1.0f // body-frame rate controller timeout in seconds -- GitLab