Plane: Quadplane: force convertions of Q_M_PMW_* params if invalid and add arming check

This commit is contained in:
Iampete1 2022-06-02 18:45:31 +01:00 committed by Andrew Tridgell
parent eed14b3688
commit 34609d327d
2 changed files with 15 additions and 3 deletions

View File

@ -167,6 +167,10 @@ bool AP_Arming_Plane::quadplane_checks(bool display_failure)
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Bad parameter: %s", failure_msg);
ret = false;
}
if (!plane.quadplane.motors->check_mot_pwm_params()) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check Q_M_PWM_MIN/MAX");
ret = false;
}
if ((plane.quadplane.options & QuadPlane::OPTION_ONLY_ARM_IN_QMODE_OR_AUTO) != 0) {
if (!plane.control_mode->is_vtol_mode() && (plane.control_mode != &plane.mode_auto) && (plane.control_mode != &plane.mode_guided)) {

View File

@ -534,14 +534,16 @@ const AP_Param::ConversionInfo q_conversion_table[] = {
{ Parameters::k_param_quadplane, 1467, AP_PARAM_FLOAT, "Q_TILT_FIX_ANGLE" },
{ Parameters::k_param_quadplane, 1531, AP_PARAM_FLOAT, "Q_TILT_FIX_GAIN" },
{ Parameters::k_param_quadplane, 22, AP_PARAM_INT16, "Q_M_PWM_MIN" },
{ Parameters::k_param_quadplane, 23, AP_PARAM_INT16, "Q_M_PWM_MAX" },
// PARAMETER_CONVERSION - Added: Jan-2022
{ Parameters::k_param_quadplane, 33, AP_PARAM_FLOAT, "Q_WVANE_GAIN" }, // Moved from quadplane to weathervane library
{ Parameters::k_param_quadplane, 34, AP_PARAM_FLOAT, "Q_WVANE_ANG_MIN" }, // Q_WVANE_MINROLL moved from quadplane to weathervane library
};
// PARAMETER_CONVERSION - Added: Oct-2021
const AP_Param::ConversionInfo mot_pwm_conversion_table[] = {
{ Parameters::k_param_quadplane, 22, AP_PARAM_INT16, "Q_M_PWM_MIN" },
{ Parameters::k_param_quadplane, 23, AP_PARAM_INT16, "Q_M_PWM_MAX" },
};
QuadPlane::QuadPlane(AP_AHRS &_ahrs) :
ahrs(_ahrs)
@ -716,6 +718,12 @@ bool QuadPlane::setup(void)
motors->set_update_rate(rc_speed);
attitude_control->parameter_sanity_check();
// Try to convert mot PWM params, if still invalid force conversion
AP_Param::convert_old_parameters(&mot_pwm_conversion_table[0], ARRAY_SIZE(mot_pwm_conversion_table));
if (!motors->check_mot_pwm_params()) {
AP_Param::convert_old_parameters(&mot_pwm_conversion_table[0], ARRAY_SIZE(mot_pwm_conversion_table), AP_Param::CONVERT_FLAG_FORCE);
}
// setup the trim of any motors used by AP_Motors so I/O board
// failsafe will disable motors
uint32_t mask = plane.quadplane.motors->get_motor_mask();