From eac52fe08ff8db36d20b250dfc26db4247f45bb9 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 26 Nov 2021 22:46:10 +0000 Subject: [PATCH] Plane: quadplane: don't ouput VTOL throttle on tiltrotor with no VTOL motors and till fully forward --- ArduPlane/quadplane.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 8b88319192..7aa203919e 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -2200,7 +2200,8 @@ void QuadPlane::vtol_position_controller(void) const float stop_distance = stopping_distance(); - if (poscontrol.get_state() == QPOS_AIRBRAKE) { + if (poscontrol.get_state() == QPOS_AIRBRAKE && !(tiltrotor.enabled() && !tiltrotor.has_vtol_motor() && (tiltrotor.current_tilt >= tiltrotor.get_fully_forward_tilt()))) { + // don't ouput VTOL throttle on tiltrotors if there are no fixed VTOL motors and the tilt is still forward hold_hover(0); }