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
This commit is contained in:
Andrew Tridgell 2021-02-28 10:31:11 +11:00
parent 319368e4b7
commit 44df1dd0ca

View File

@ -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);