Plane: continue limiting pitch during last phase of transition

this prevents a very high pitch demand causing the plane to slow down
to below assist speed
This commit is contained in:
Andrew Tridgell 2016-01-20 18:30:48 +11:00
parent 926c37a876
commit 115d089904
1 changed files with 2 additions and 0 deletions

View File

@ -755,6 +755,8 @@ void QuadPlane::update_transition(void)
if (transition_state < TRANSITION_TIMER) {
// set a single loop pitch limit in TECS
plane.TECS_controller.set_pitch_max_limit(transition_pitch_max);
} else if (transition_state < TRANSITION_DONE) {
plane.TECS_controller.set_pitch_max_limit((transition_pitch_max+1)*2);
}
switch (transition_state) {