mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
Plane: backport fix for AirMode on quadplanes
This commit is contained in:
parent
c3362aef9e
commit
1695460716
@ -309,6 +309,7 @@ bool RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const AuxSwit
|
|||||||
switch (ch_flag) {
|
switch (ch_flag) {
|
||||||
case AuxSwitchPos::HIGH:
|
case AuxSwitchPos::HIGH:
|
||||||
plane.quadplane.air_mode = AirMode::ON;
|
plane.quadplane.air_mode = AirMode::ON;
|
||||||
|
plane.quadplane.throttle_wait = false;
|
||||||
break;
|
break;
|
||||||
case AuxSwitchPos::MIDDLE:
|
case AuxSwitchPos::MIDDLE:
|
||||||
break;
|
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);
|
RC_Channel::do_aux_function_armdisarm(ch_flag);
|
||||||
if (plane.arming.is_armed()) {
|
if (plane.arming.is_armed()) {
|
||||||
plane.quadplane.air_mode = AirMode::ON;
|
plane.quadplane.air_mode = AirMode::ON;
|
||||||
|
plane.quadplane.throttle_wait = false;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
@ -1327,8 +1327,10 @@ void QuadPlane::set_armed(bool armed)
|
|||||||
|
|
||||||
// re-init throttle wait on arm and disarm, to prevent rudder
|
// re-init throttle wait on arm and disarm, to prevent rudder
|
||||||
// arming on 2nd flight causing yaw
|
// arming on 2nd flight causing yaw
|
||||||
|
if (!air_mode_active()) {
|
||||||
init_throttle_wait();
|
init_throttle_wait();
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user