From 040e08f4b1401d2d2cb072205ee51fafeb4aafe2 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 12 Feb 2022 20:23:48 +0000 Subject: [PATCH] Plane: tailsitter: dont check if flying its always true in vtol transtion --- ArduPlane/tailsitter.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/tailsitter.cpp b/ArduPlane/tailsitter.cpp index 8725524013..62c7c9cbdc 100644 --- a/ArduPlane/tailsitter.cpp +++ b/ArduPlane/tailsitter.cpp @@ -294,7 +294,7 @@ void Tailsitter::output(void) // handle forward flight modes and transition to VTOL modes if (!active() || in_vtol_transition()) { // get FW controller throttle demand and mask of motors enabled during forward flight - if (hal.util->get_soft_armed() && in_vtol_transition() && !quadplane.throttle_wait && quadplane.is_flying()) { + if (hal.util->get_soft_armed() && in_vtol_transition() && !quadplane.throttle_wait) { /* during transitions to vtol mode set the throttle to hover thrust, center the rudder */