From 71e8a21d44435b6f4f9690a007e233c1c5387f84 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 24 May 2023 13:34:46 +1000 Subject: [PATCH] Plane: backport fix for AirMode on quadplanes --- ArduPlane/RC_Channel.cpp | 2 ++ ArduPlane/quadplane.cpp | 4 +++- 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/ArduPlane/RC_Channel.cpp b/ArduPlane/RC_Channel.cpp index 42985b16ea..2fbb0feede 100644 --- a/ArduPlane/RC_Channel.cpp +++ b/ArduPlane/RC_Channel.cpp @@ -309,6 +309,7 @@ bool RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const AuxSwit switch (ch_flag) { case AuxSwitchPos::HIGH: plane.quadplane.air_mode = AirMode::ON; + plane.quadplane.throttle_wait = false; break; case AuxSwitchPos::MIDDLE: break; @@ -359,6 +360,7 @@ bool RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const AuxSwit RC_Channel::do_aux_function_armdisarm(ch_flag); if (plane.arming.is_armed()) { plane.quadplane.air_mode = AirMode::ON; + plane.quadplane.throttle_wait = false; } break; diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 79768ca6a1..ebecaaff3d 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1327,7 +1327,9 @@ void QuadPlane::set_armed(bool armed) // re-init throttle wait on arm and disarm, to prevent rudder // arming on 2nd flight causing yaw - init_throttle_wait(); + if (!air_mode_active()) { + init_throttle_wait(); + } }