From f480f4e946ebcd348d70d8c146ad1f0e4af962f3 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 16 Nov 2020 17:28:31 +0000 Subject: [PATCH] Plane: tailsitter: fix Qassist back - transision --- ArduPlane/tailsitter.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduPlane/tailsitter.cpp b/ArduPlane/tailsitter.cpp index 18a6ae83fd..e65ecd7fe2 100644 --- a/ArduPlane/tailsitter.cpp +++ b/ArduPlane/tailsitter.cpp @@ -114,7 +114,8 @@ void QuadPlane::tailsitter_output(void) // handle Copter controller // the MultiCopter rate controller has already been run in an earlier call // to motors_output() from quadplane.update(), unless we are in assisted flight - if (assisted_flight && is_tailsitter_in_fw_flight()) { + // tailsitter in TRANSITION_ANGLE_WAIT_FW is not really in assisted flight, its still in a VTOL mode + if (assisted_flight && (transition_state != TRANSITION_ANGLE_WAIT_FW)) { hold_stabilize(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * 0.01f); motors_output(true);