AC_AttControl: FF and accel limiting off by default

Also adjust parameter ranges used by GCSs
This commit is contained in:
Randy Mackay 2014-07-17 16:22:32 +09:00
parent e339149044
commit c2f8571f37
2 changed files with 12 additions and 9 deletions

View File

@ -12,7 +12,7 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] PROGMEM = {
// @DisplayName: Angle Rate Roll-Pitch max
// @Description: maximum rotation rate in roll/pitch axis requested by angle controller used in stabilize, loiter, rtl, auto flight modes
// @Units: Centi-Degrees/Sec
// @Range: 90000 250000
// @Range: 9000 36000
// @Increment: 500
// @User: Advanced
AP_GROUPINFO("RATE_RP_MAX", 0, AC_AttitudeControl, _angle_rate_rp_max, AC_ATTITUDE_CONTROL_RATE_RP_MAX_DEFAULT),
@ -21,7 +21,7 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] PROGMEM = {
// @DisplayName: Angle Rate Yaw max
// @Description: maximum rotation rate in roll/pitch axis requested by angle controller used in stabilize, loiter, rtl, auto flight modes
// @Units: Centi-Degrees/Sec
// @Range: 90000 250000
// @Range: 4500 18000
// @Increment: 500
// @User: Advanced
AP_GROUPINFO("RATE_Y_MAX", 1, AC_AttitudeControl, _angle_rate_y_max, AC_ATTITUDE_CONTROL_RATE_Y_MAX_DEFAULT),
@ -39,7 +39,9 @@ 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
// @Values: 36000:Very Soft, 54000:Soft, 90000:Medium, 126000:Crisp, 162000:Very Crisp
// @Range: 0 180000
// @Increment: 1000
// @Values: 0:Disabled, 72000:Slow, 108000:Medium, 162000:Fast
// @User: Advanced
AP_GROUPINFO("ACCEL_RP_MAX", 3, AC_AttitudeControl, _accel_rp_max, AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT),
@ -47,8 +49,9 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] PROGMEM = {
// @DisplayName: Acceleration Max for Yaw
// @Description: Maximum acceleration in yaw axis
// @Units: Centi-Degrees/Sec/Sec
// @Range: 20000 100000
// @Increment: 100
// @Range: 0 72000
// @Values: 0:Disabled, 18000:Slow, 36000:Medium, 54000:Fast
// @Increment: 1000
// @User: Advanced
AP_GROUPINFO("ACCEL_Y_MAX", 4, AC_AttitudeControl, _accel_y_max, AC_ATTITUDE_CONTROL_ACCEL_Y_MAX_DEFAULT),

View File

@ -19,10 +19,10 @@
// To-Do: change the name or move to AP_Math?
#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_RATE_Y_MAX_DEFAULT 9000 // 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 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_CONTROL_ACCEL_RP_MAX_DEFAULT 0 // default maximum acceleration for roll/pitch axis in centi-degrees/sec/sec
#define AC_ATTITUDE_CONTROL_ACCEL_Y_MAX_DEFAULT 0 // 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)
@ -41,7 +41,7 @@
#define AC_ATTITUDE_RATE_RP_PID_DTERM_FILTER 20 // D-term filter rate cutoff frequency for Roll and Pitch rate controllers
#define AC_ATTITUDE_RATE_Y_PID_DTERM_FILTER 5 // D-term filter rate cutoff frequency for Yaw rate controller
#define AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT 1 // body-frame rate feedforward enabled by default
#define AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT 0 // body-frame rate feedforward enabled by default
class AC_AttitudeControl {
public: