From 6cef4c15d1a908aa2d15a0f19963ecd09da9260b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 24 Feb 2023 20:13:47 +1100 Subject: [PATCH] Plane: re-init throttle wait on quadplane arm and disarm this prevents yaw from rudder arming on 2nd flight --- ArduPlane/quadplane.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index e4a009eeb9..79768ca6a1 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1324,6 +1324,10 @@ void QuadPlane::set_armed(bool armed) if (plane.control_mode == &plane.mode_guided) { guided_wait_takeoff = armed; } + + // re-init throttle wait on arm and disarm, to prevent rudder + // arming on 2nd flight causing yaw + init_throttle_wait(); }