Plane: limit pitch to zero during airspeed wait VTOL mode

This commit is contained in:
Andrew Tridgell 2016-01-09 21:50:59 +11:00
parent 4f9927beda
commit 4adda34439

View File

@ -727,6 +727,11 @@ void QuadPlane::update_transition(void)
assisted_flight = false;
}
if (transition_state < TRANSITION_TIMER) {
// set a single loop pitch limit in TECS
plane.TECS_controller.set_pitch_max_limit(0);
}
switch (transition_state) {
case TRANSITION_AIRSPEED_WAIT: {
// we hold in hover until the required airspeed is reached