From 115d089904f91818ffc4ad9e6eb4cd9bc4bedd1f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 20 Jan 2016 18:30:48 +1100 Subject: [PATCH] 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 --- ArduPlane/quadplane.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index e692574959..cb66f31993 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -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) {