AC_AttControl: increase default rp accel to 900deg/s/s

This commit is contained in:
Randy Mackay 2014-04-04 17:47:11 +09:00
parent 92d212abf1
commit 5876a2fe47
2 changed files with 2 additions and 3 deletions

View File

@ -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),

View File

@ -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