From 44df1dd0ca78c3409d11ee898d52cd36e85087f3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 28 Feb 2021 10:31:11 +1100 Subject: [PATCH] Plane: fixed the pitch control in transition for tilt rotors this fixes an issue found by Henry. If level transition is set when transitioning to FBWA from a Q mode, and the pilot pulls back on the pitch stick to demand pitch up then the plane would go into a high-alpha flight state with low vertical throttle so it would not climb, resulting in it never getting past airspeed wait state --- ArduPlane/quadplane.cpp | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index a12f7a2c8a..8db411ebae 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1821,11 +1821,13 @@ void QuadPlane::update_transition(void) } assisted_flight = true; - // do not allow a climb on the quad motors during transition - // a climb would add load to the airframe, and prolongs the - // transition + // do not allow a climb on the quad motors during transition a + // climb would add load to the airframe, and prolongs the + // transition. We don't limit the climb rate on tilt rotors as + // otherwise the plane can end up in high-alpha flight with + // low VTOL thrust and may not complete a transition float climb_rate_cms = assist_climb_rate_cms(); - if (options & OPTION_LEVEL_TRANSITION) { + if ((options & OPTION_LEVEL_TRANSITION) && tilt.tilt_mask == 0) { climb_rate_cms = MIN(climb_rate_cms, 0.0f); } hold_hover(climb_rate_cms);