From 807c05c715287f24456fb32bde20f69851606bab Mon Sep 17 00:00:00 2001 From: Peter Hall <33176108+IamPete1@users.noreply.github.com> Date: Sun, 19 Jan 2020 16:46:36 +0000 Subject: [PATCH] Plane: tilitrotor: allow motor test --- ArduPlane/tiltrotor.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/ArduPlane/tiltrotor.cpp b/ArduPlane/tiltrotor.cpp index 18bdf6969a..2588a182eb 100644 --- a/ArduPlane/tiltrotor.cpp +++ b/ArduPlane/tiltrotor.cpp @@ -75,11 +75,13 @@ void QuadPlane::tiltrotor_continuous_update(void) if (!hal.util->get_soft_armed()) { tilt.current_throttle = 0; } else { + // prevent motor shutdown + tilt.motors_active = true; + } + if (!motor_test.running) { // 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, plane.rudder_dt); - // prevent motor shutdown - tilt.motors_active = true; } return; } @@ -373,7 +375,8 @@ void QuadPlane::tiltrotor_vectored_yaw(void) */ void QuadPlane::tiltrotor_bicopter(void) { - if (tilt.tilt_type != TILT_TYPE_BICOPTER) { + if (tilt.tilt_type != TILT_TYPE_BICOPTER || motor_test.running) { + // don't override motor test with motors_output return; }