Plane: Quadplane remove THR_MIN_PWM and THR_MAX_PWM

This commit is contained in:
Iampete1 2021-09-04 18:16:53 +01:00 committed by Randy Mackay
parent d1d6342165
commit 30c9cccf78
4 changed files with 10 additions and 23 deletions

View File

@ -81,7 +81,7 @@ void AP_AdvancedFailsafe_Plane::setup_IO_failsafe(void)
if (plane.quadplane.available()) {
// setup AP_Motors outputs for failsafe
uint16_t mask = plane.quadplane.motors->get_motor_mask();
hal.rcout->set_failsafe_pwm(mask, plane.quadplane.thr_min_pwm);
hal.rcout->set_failsafe_pwm(mask, plane.quadplane.motors->get_pwm_output_min());
}
#endif
}

View File

@ -43,6 +43,9 @@ void QuadPlane::motor_test_output()
int16_t pwm = 0; // pwm that will be output to the motors
// calculate pwm based on throttle type
const int16_t thr_min_pwm = motors->get_pwm_output_min();
const int16_t thr_max_pwm = motors->get_pwm_output_max();
switch (motor_test.throttle_type) {
case MOTOR_TEST_THROTTLE_PERCENT:
// sanity check motor_test.throttle value

View File

@ -82,23 +82,8 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
// @User: Standard
AP_GROUPINFO("RC_SPEED", 21, QuadPlane, rc_speed, 490),
// @Param: THR_MIN_PWM
// @DisplayName: Minimum PWM output
// @Description: This is the minimum PWM output for the quad motors
// @Units: PWM
// @Range: 800 2200
// @Increment: 1
// @User: Standard
AP_GROUPINFO("THR_MIN_PWM", 22, QuadPlane, thr_min_pwm, 1000),
// @Param: THR_MAX_PWM
// @DisplayName: Maximum PWM output
// @Description: This is the maximum PWM output for the quad motors
// @Units: PWM
// @Range: 800 2200
// @Increment: 1
// @User: Standard
AP_GROUPINFO("THR_MAX_PWM", 23, QuadPlane, thr_max_pwm, 2000),
// 22: THR_MIN_PWM
// 23: THR_MAX_PWM
// @Param: ASSIST_SPEED
// @DisplayName: Quadplane assistance speed
@ -507,6 +492,9 @@ const AP_Param::ConversionInfo q_conversion_table[] = {
{ Parameters::k_param_quadplane, 55, AP_PARAM_FLOAT, "Q_TILT_YAW_ANGLE" },
{ 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" },
};
@ -682,7 +670,7 @@ bool QuadPlane::setup(void)
// failsafe will disable motors
for (uint8_t i=0; i<8; i++) {
SRV_Channel::Aux_servo_function_t func = SRV_Channels::get_motor_function(i);
SRV_Channels::set_failsafe_pwm(func, thr_min_pwm);
SRV_Channels::set_failsafe_pwm(func, motors->get_pwm_output_min());
}
transition_state = TRANSITION_DONE;

View File

@ -286,10 +286,6 @@ private:
AP_Int16 rc_speed;
// min and max PWM for throttle
AP_Int16 thr_min_pwm;
AP_Int16 thr_max_pwm;
// speed below which quad assistance is given
AP_Float assist_speed;