mirror of https://github.com/ArduPilot/ardupilot
Copter: add ANGLE_RATE_MAX param
Limits the maximum rotation rate requested by the angle controller which is used in stabilize, loiter, rtl and auto flight modes
This commit is contained in:
parent
9176bf2e97
commit
8386b658e9
|
@ -36,7 +36,7 @@ get_stabilize_roll(int32_t target_angle)
|
|||
|
||||
// constrain the target rate
|
||||
if (!ap.disable_stab_rate_limit) {
|
||||
target_rate = constrain_int32(target_rate, -STABILIZE_RATE_LIMIT, STABILIZE_RATE_LIMIT);
|
||||
target_rate = constrain_int32(target_rate, -g.angle_rate_max, g.angle_rate_max);
|
||||
}
|
||||
|
||||
// set targets for rate controller
|
||||
|
@ -54,7 +54,7 @@ get_stabilize_pitch(int32_t target_angle)
|
|||
|
||||
// constrain the target rate
|
||||
if (!ap.disable_stab_rate_limit) {
|
||||
target_rate = constrain_int32(target_rate, -STABILIZE_RATE_LIMIT, STABILIZE_RATE_LIMIT);
|
||||
target_rate = constrain_int32(target_rate, -g.angle_rate_max, g.angle_rate_max);
|
||||
}
|
||||
|
||||
// set targets for rate controller
|
||||
|
|
|
@ -92,7 +92,8 @@ public:
|
|||
k_param_angle_max,
|
||||
k_param_gps_hdop_good,
|
||||
k_param_battery,
|
||||
k_param_fs_batt_mah, // 37
|
||||
k_param_fs_batt_mah,
|
||||
k_param_angle_rate_max, // 38
|
||||
|
||||
// 65: AP_Limits Library
|
||||
k_param_limits = 65, // deprecated - remove
|
||||
|
@ -302,6 +303,7 @@ public:
|
|||
AP_Int8 rssi_pin;
|
||||
AP_Int8 wp_yaw_behavior; // controls how the autopilot controls yaw during missions
|
||||
AP_Int16 angle_max; // maximum lean angle of the copter in centi-degrees
|
||||
AP_Int32 angle_rate_max; // maximum rotation rate in roll/pitch axis requested by angle controller used in stabilize, loiter, rtl, auto flight modes
|
||||
|
||||
// Waypoints
|
||||
//
|
||||
|
|
|
@ -416,6 +416,13 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||
// @User: Advanced
|
||||
GSCALAR(angle_max, "ANGLE_MAX", DEFAULT_ANGLE_MAX),
|
||||
|
||||
// @Param: ANGLE_RATE_MAX
|
||||
// @DisplayName: Angle Rate max
|
||||
// @Description: maximum rotation rate in roll/pitch axis requested by angle controller used in stabilize, loiter, rtl, auto flight modes
|
||||
// @Range 90000 250000
|
||||
// @User: Advanced
|
||||
GSCALAR(angle_rate_max, "ANGLE_RATE_MAX", ANGLE_RATE_MAX),
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// @Group: HS1_
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
||||
|
|
|
@ -756,10 +756,6 @@
|
|||
# define STABILIZE_PITCH_IMAX 0
|
||||
#endif
|
||||
|
||||
#ifndef STABILIZE_RATE_LIMIT
|
||||
# define STABILIZE_RATE_LIMIT 18000
|
||||
#endif
|
||||
|
||||
#ifndef STABILIZE_YAW_P
|
||||
# define STABILIZE_YAW_P 4.5f // increase for more aggressive Yaw Hold, decrease if it's bouncy
|
||||
#endif
|
||||
|
@ -784,6 +780,9 @@
|
|||
#ifndef DEFAULT_ANGLE_MAX
|
||||
# define DEFAULT_ANGLE_MAX 4500 // ANGLE_MAX parameters default value
|
||||
#endif
|
||||
#ifndef ANGLE_RATE_MAX
|
||||
# define ANGLE_RATE_MAX 18000 // default maximum rotation rate in roll/pitch axis requested by angle controller used in stabilize, loiter, rtl, auto flight modes
|
||||
#endif
|
||||
#ifndef RATE_ROLL_P
|
||||
# define RATE_ROLL_P 0.150f
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue