From 4848ac9166b0654dbb3c599d0457564ae8c9d46c Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 17 Nov 2021 18:44:48 +0000 Subject: [PATCH] Plane: quadplane: don't use `is_active_z()`, becasue its wrong --- ArduPlane/quadplane.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 141f6dbd2b..7ec7d28edd 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -892,7 +892,7 @@ void QuadPlane::run_z_controller(void) // never run Z controller in tailsitter transtion return; } - if (!pos_control->is_active_z()) { + if ((now - last_pidz_active_ms) > 20) { // set vertical speed and acceleration limits pos_control->set_max_speed_accel_z(-get_pilot_velocity_z_max_dn(), pilot_velocity_z_max_up, pilot_accel_z);