mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Motors: fix regression for tiltrotors
This commit is contained in:
parent
134e7fb81c
commit
35928a8d05
@ -707,7 +707,9 @@ void AP_MotorsMulticopter::output_motor_mask(float thrust, uint8_t mask, float r
|
||||
*/
|
||||
float diff_thrust = get_roll_factor(i) * rudder_dt * 0.5f;
|
||||
set_actuator_with_slew(_actuator[i], thrust_to_actuator(thrust + diff_thrust));
|
||||
rc_write(i, output_to_pwm(_actuator[i]));
|
||||
int16_t pwm_output = get_pwm_output_min() +
|
||||
(get_pwm_output_max()-get_pwm_output_min()) * _actuator[i];
|
||||
rc_write(i, pwm_output);
|
||||
} else {
|
||||
rc_write(i, get_pwm_output_min());
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user