AP_Motors: smoother ramp down in output_motor_mask

stop changing motors outside the given mask in output_motor_mask,
which gives smoother ramp down in tilt quadplanes when we are
transitioning to forward flight

thanks to Pete for the suggestion
This commit is contained in:
Andrew Tridgell 2024-03-05 08:04:53 +11:00
parent 2b784e01f9
commit 171da3dd08
2 changed files with 7 additions and 6 deletions

View File

@ -733,8 +733,8 @@ void AP_MotorsMulticopter::output_motor_mask(float thrust, uint16_t mask, float
_motor_mask_override = mask;
for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
if (motor_enabled[i]) {
if ((mask & (1U << i)) && armed() && get_interlock()) {
if (motor_enabled[i] && (mask & (1U << i)) != 0) {
if (armed() && get_interlock()) {
/*
apply rudder mixing differential thrust
copter frame roll is plane frame yaw as this only
@ -742,11 +742,12 @@ void AP_MotorsMulticopter::output_motor_mask(float thrust, uint16_t mask, float
*/
float diff_thrust = get_roll_factor(i) * rudder_dt * 0.5f;
set_actuator_with_slew(_actuator[i], thrust + diff_thrust);
int16_t pwm_output = pwm_min + pwm_range * _actuator[i];
rc_write(i, pwm_output);
} else {
rc_write(i, pwm_min);
// zero throttle
_actuator[i] = 0.0;
}
int16_t pwm_output = pwm_min + pwm_range * _actuator[i];
rc_write(i, pwm_output);
}
}
}

View File

@ -92,7 +92,7 @@ void AP_MotorsTri::output_to_motors()
// sends minimum values out to the motors
for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
if (motor_enabled_mask(i)) {
rc_write(AP_MOTORS_MOT_1+i, output_to_pwm(0));
_actuator[AP_MOTORS_MOT_1+i] = 0;
}
}
rc_write_angle(AP_MOTORS_CH_TRI_YAW, 0);