From fb1f6b57ad21fb476a548cfe19fd65cc7a2f6282 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 17 Nov 2021 18:44:08 +0000 Subject: [PATCH] Plane: Quadplane: never run Z controller if motors are not throttle unlimited --- ArduPlane/quadplane.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 635534d191..141f6dbd2b 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -884,6 +884,9 @@ void QuadPlane::hold_stabilize(float throttle_in) // run the multicopter Z controller void QuadPlane::run_z_controller(void) { + if (motors->get_spool_state() != AP_Motors::SpoolState::THROTTLE_UNLIMITED ) { + return; + } const uint32_t now = AP_HAL::millis(); if (tailsitter.in_vtol_transition(now)) { // never run Z controller in tailsitter transtion