From b6519c88a5056ae70f4d1a9fdbb329e85011ad52 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 13 Sep 2018 20:57:10 +1000 Subject: [PATCH] Plane: fixed a bug in Q_ASSIST_ modes for tiltrotors when a tilt-rotor drops below Q_ASSIST_SPEED we need to keep it in the airspeed wait state until it has regained airspeed, otherwise we will end up with too low throttle --- ArduPlane/quadplane.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 24cc617dfa..774a5dcea4 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1277,8 +1277,10 @@ void QuadPlane::update_transition(void) } } - // if rotors are fully forward then we are not transitioning - if (tiltrotor_fully_fwd()) { + // if rotors are fully forward then we are not transitioning, + // unless we are waiting for airspeed to increase (in which case + // the tilt will decrease rapidly) + if (tiltrotor_fully_fwd() && transition_state != TRANSITION_AIRSPEED_WAIT) { transition_state = TRANSITION_DONE; }