Plane: backport fix for AirMode on quadplanes

This commit is contained in:
Andrew Tridgell 2023-05-24 13:34:46 +10:00 committed by Randy Mackay
parent 99a17bde11
commit 71e8a21d44
2 changed files with 5 additions and 1 deletions

View File

@ -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;

View File

@ -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();
}
}