Copter: integrate ANGLE_MAX move to ATC

This commit is contained in:
Randy Mackay
2026-01-21 09:58:56 +09:00
committed by Peter Barker
parent 40584a1cf1
commit 947697ec04
8 changed files with 15 additions and 29 deletions

View File

@@ -218,12 +218,6 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
check_failed(Check::PARAMETERS, display_failure, "FS_GCS_ENABLE=2 removed, see FS_OPTIONS");
}
// lean angle parameter check
if (copter.aparm.angle_max < 1000 || copter.aparm.angle_max > 8000) {
check_failed(Check::PARAMETERS, display_failure, "Check ANGLE_MAX");
return false;
}
// acro balance parameter check
#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED
if (is_negative(copter.g.acro_balance_roll) || is_negative(copter.g.acro_balance_pitch) ||
@@ -601,7 +595,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
// check lean angle
if (check_enabled(Check::INS)) {
if (degrees(acosf(ahrs.cos_roll()*ahrs.cos_pitch()))*100.0f > copter.aparm.angle_max) {
if (acosf(ahrs.cos_roll()*ahrs.cos_pitch()) > copter.attitude_control->lean_angle_max_rad()) {
check_failed(Check::INS, true, "Leaning");
return false;
}

View File

@@ -236,9 +236,6 @@ public:
private:
// key aircraft parameters passed to multiple libraries
AP_MultiCopter aparm;
// Global parameters are all contained within the 'g' class.
Parameters g;
ParametersG2 g2;

View File

@@ -273,15 +273,6 @@ const AP_Param::Info Copter::var_info[] = {
// @Range: 0 127
// @User: Advanced
GSCALAR(disarm_delay, "DISARM_DELAY", AUTO_DISARMING_DELAY),
// @Param: ANGLE_MAX
// @DisplayName: Angle Max
// @Description: Maximum lean angle in all flight modes
// @Units: cdeg
// @Increment: 10
// @Range: 1000 8000
// @User: Advanced
ASCALAR(angle_max, "ANGLE_MAX", DEFAULT_ANGLE_MAX),
#if MODE_POSHOLD_ENABLED
// @Param: PHLD_BRAKE_RATE

View File

@@ -110,7 +110,7 @@ public:
k_param_ch8_option_old, // deprecated
k_param_arming_check_old, // deprecated - remove
k_param_sprayer,
k_param_angle_max,
k_param_angle_max, // remove
k_param_gps_hdop_good,
k_param_battery,
k_param_fs_batt_mah, // unused - moved to AP_BattMonitor

View File

@@ -470,8 +470,9 @@
#ifndef ROLL_PITCH_YAW_INPUT_MAX
# define ROLL_PITCH_YAW_INPUT_MAX 4500 // roll, pitch and yaw input range
#endif
#ifndef DEFAULT_ANGLE_MAX
# define DEFAULT_ANGLE_MAX 3000 // ANGLE_MAX parameters default value
#ifdef DEFAULT_ANGLE_MAX
#error "DEFAULT_ANGLE_MAX definition replaced with AC_ATTITUDE_CONTROL_ANGLE_MAX_DEFAULT (in degrees)"
#endif
//////////////////////////////////////////////////////////////////////////////

View File

@@ -118,7 +118,7 @@ bool ModeFlowHold::init(bool ignore_checks)
void ModeFlowHold::flowhold_flow_to_angle(Vector2f &bf_angles_rad, bool stick_input)
{
uint32_t now = AP_HAL::millis();
const float angle_max_rad = cd_to_rad(copter.aparm.angle_max);
const float angle_max_rad = copter.attitude_control->lean_angle_max_rad();
// get corrected raw flow rate
Vector2f raw_flow_rads = copter.optflow.flowRate() - copter.optflow.bodyRate();
@@ -319,7 +319,7 @@ void ModeFlowHold::run()
// calculate alt-hold angles
int16_t roll_in = copter.channel_roll->get_control_in();
int16_t pitch_in = copter.channel_pitch->get_control_in();
const float angle_max_rad = cd_to_rad(copter.aparm.angle_max);
const float angle_max_rad = copter.attitude_control->lean_angle_max_rad();
float target_roll_rad, target_pitch_rad;
get_pilot_desired_lean_angles_rad(target_roll_rad, target_pitch_rad, attitude_control->lean_angle_max_rad(), attitude_control->get_althold_lean_angle_max_rad());

View File

@@ -479,7 +479,7 @@ void ModePosHold::run()
}
// constrain target pitch/roll angles
const float angle_max_rad = cd_to_rad(copter.aparm.angle_max);
const float angle_max_rad = copter.attitude_control->lean_angle_max_rad();
roll_rad = constrain_float(roll_rad, -angle_max_rad, angle_max_rad);
pitch_rad = constrain_float(pitch_rad, -angle_max_rad, angle_max_rad);
@@ -582,7 +582,7 @@ void ModePosHold::update_wind_comp_estimate()
}
// limit acceleration
const float accel_lim_mss = tanf(cd_to_rad(POSHOLD_WIND_COMP_LEAN_PCT_MAX * copter.aparm.angle_max)) * GRAVITY_MSS;
const float accel_lim_mss = tanf(POSHOLD_WIND_COMP_LEAN_PCT_MAX * copter.attitude_control->lean_angle_max_rad()) * GRAVITY_MSS;
const float wind_comp_ef_len = wind_comp_ne_mss.length();
if (!is_zero(accel_lim_mss) && (wind_comp_ef_len > accel_lim_mss)) {
wind_comp_ne_mss *= accel_lim_mss / wind_comp_ef_len;

View File

@@ -441,15 +441,15 @@ void Copter::allocate_motors(void)
#if FRAME_CONFIG != HELI_FRAME
if ((AP_Motors::motor_frame_class)g2.frame_class.get() == AP_Motors::MOTOR_FRAME_6DOF_SCRIPTING) {
#if AP_SCRIPTING_ENABLED
attitude_control = NEW_NOTHROW AC_AttitudeControl_Multi_6DoF(*ahrs_view, aparm, *motors);
attitude_control = NEW_NOTHROW AC_AttitudeControl_Multi_6DoF(*ahrs_view, *motors);
attitude_control_var_info = AC_AttitudeControl_Multi_6DoF::var_info;
#endif // AP_SCRIPTING_ENABLED
} else {
attitude_control = NEW_NOTHROW AC_AttitudeControl_Multi(*ahrs_view, aparm, *motors);
attitude_control = NEW_NOTHROW AC_AttitudeControl_Multi(*ahrs_view, *motors);
attitude_control_var_info = AC_AttitudeControl_Multi::var_info;
}
#else
attitude_control = NEW_NOTHROW AC_AttitudeControl_Heli(*ahrs_view, aparm, *motors);
attitude_control = NEW_NOTHROW AC_AttitudeControl_Heli(*ahrs_view, *motors);
attitude_control_var_info = AC_AttitudeControl_Heli::var_info;
#endif
if (attitude_control == nullptr) {
@@ -523,6 +523,9 @@ void Copter::allocate_motors(void)
convert_prx_parameters();
#endif
// upgrade attitude controller parameters
copter.attitude_control->convert_parameters();
// upgrade position controller parameters
copter.pos_control->convert_parameters();