From 214434a2d7e998c9b889cb6e6b52edbb59feeb98 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 30 Oct 2017 08:47:04 +1100 Subject: [PATCH] Plane: fixed tailsitter ANGLE_WAIT transition we need vtol control during transition from hover to fwd flight --- ArduPlane/tailsitter.cpp | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/ArduPlane/tailsitter.cpp b/ArduPlane/tailsitter.cpp index 8ed79d33e8..2275774e68 100644 --- a/ArduPlane/tailsitter.cpp +++ b/ArduPlane/tailsitter.cpp @@ -31,7 +31,17 @@ bool QuadPlane::is_tailsitter(void) */ bool QuadPlane::tailsitter_active(void) { - return is_tailsitter() && in_vtol_mode(); + if (!is_tailsitter()) { + return false; + } + if (in_vtol_mode()) { + return true; + } + // check if we are in ANGLE_WAIT transition + if (transition_state == TRANSITION_ANGLE_WAIT) { + return true; + } + return false; } /*