From b1266603a6ab451ed7156cb8193b61e5f99803b4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 2 Apr 2016 19:53:48 +1100 Subject: [PATCH] Plane: setup immediate pitch limit on quadplane takeoff this prevents a single loop with large pitch down demand --- ArduPlane/quadplane.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 85f90067d1..be5385782b 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1182,6 +1182,7 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd) return false; } transition_state = TRANSITION_AIRSPEED_WAIT; + plane.TECS_controller.set_pitch_max_limit(transition_pitch_max); return true; }