From d07f8aa42b4ada7dad322eea50274380f4cb17e0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 25 Apr 2018 17:21:11 +1000 Subject: [PATCH] Plane: fixed a bug in transition to QSTABILIZE for tailsitters this bug was found bug Marco on his tailsitter. It resulted in zero throttle for 2s in transition from FBWA to QSTABILIZE --- ArduPlane/quadplane.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 712cb85c82..affd7ef85a 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -874,6 +874,9 @@ bool QuadPlane::is_flying(void) if (motors->get_throttle() > 0.01f && !motors->limit.throttle_lower) { return true; } + if (in_tailsitter_vtol_transition()) { + return true; + } return false; }