From 9c0ac5899f3f7c5e470bf55e31c398466bbf2368 Mon Sep 17 00:00:00 2001 From: IamPete1 <33176108+IamPete1@users.noreply.github.com> Date: Sat, 29 Dec 2018 15:42:53 +0000 Subject: [PATCH] Plane: pass rudder diffential thrust to AP_motors --- ArduPlane/tiltrotor.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/tiltrotor.cpp b/ArduPlane/tiltrotor.cpp index da3ce73d04..e14b63f5a3 100644 --- a/ArduPlane/tiltrotor.cpp +++ b/ArduPlane/tiltrotor.cpp @@ -80,7 +80,7 @@ void QuadPlane::tiltrotor_continuous_update(void) } else { // the motors are all the way forward, start using them for fwd thrust uint8_t mask = is_zero(tilt.current_throttle)?0:(uint8_t)tilt.tilt_mask.get(); - motors->output_motor_mask(tilt.current_throttle, mask); + motors->output_motor_mask(tilt.current_throttle, mask, plane.rudder_dt); // prevent motor shutdown tilt.motors_active = true; } @@ -167,7 +167,7 @@ void QuadPlane::tiltrotor_binary_update(void) if (tilt.current_tilt >= 1) { uint8_t mask = is_zero(new_throttle)?0:(uint8_t)tilt.tilt_mask.get(); // the motors are all the way forward, start using them for fwd thrust - motors->output_motor_mask(new_throttle, mask); + motors->output_motor_mask(new_throttle, mask, plane.rudder_dt); } } else { tiltrotor_binary_slew(false);