From 697efb40de0a0d3ba87bae527b3627533cee9567 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Wed, 19 Apr 2023 18:06:09 -0500 Subject: [PATCH] Plane: fix error in Qplane wait for rudder neutral --- ArduPlane/quadplane.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index c6c9a08d1f..7e4e71e0d7 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -2949,7 +2949,7 @@ void QuadPlane::takeoff_controller(void) // don't takeoff up until rudder is re-centered after rudder arming if (plane.arming.last_arm_method() == AP_Arming::Method::RUDDER && (takeoff_last_run_ms == 0 || - now - takeoff_last_run_ms < 1000) && + now - takeoff_last_run_ms > 1000) && !plane.seen_neutral_rudder && spool_state <= AP_Motors::DesiredSpoolState::GROUND_IDLE) { // start motor spinning if not spinning already so user sees it is armed