Plane: re-init throttle wait on quadplane arm and disarm

this prevents yaw from rudder arming on 2nd flight
This commit is contained in:
Andrew Tridgell 2023-02-24 20:13:47 +11:00
parent 223b91f6b4
commit 38d7bcff6b
2 changed files with 8 additions and 0 deletions

View File

@ -314,6 +314,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;
@ -364,6 +365,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

@ -1360,6 +1360,12 @@ 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
if (!air_mode_active()) {
init_throttle_wait();
}
}