diff --git a/ArduPlane/RC_Channel.cpp b/ArduPlane/RC_Channel.cpp index 24e9e95f18..058e13f64e 100644 --- a/ArduPlane/RC_Channel.cpp +++ b/ArduPlane/RC_Channel.cpp @@ -160,11 +160,16 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option, case AUX_FUNC::PARACHUTE_RELEASE: case AUX_FUNC::MODE_SWITCH_RESET: case AUX_FUNC::CRUISE: +#if HAL_QUADPLANE_ENABLED + case AUX_FUNC::ARMDISARM_AIRMODE: +#endif break; - case AUX_FUNC::Q_ASSIST: case AUX_FUNC::SOARING: +#if HAL_QUADPLANE_ENABLED + case AUX_FUNC::Q_ASSIST: case AUX_FUNC::AIRMODE: +#endif #if AP_AIRSPEED_AUTOCAL_ENABLE case AUX_FUNC::ARSPD_CALIBRATE: #endif @@ -333,6 +338,14 @@ case AUX_FUNC::ARSPD_CALIBRATE: do_aux_function_change_mode(Mode::Number::CRUISE, ch_flag); break; +#if HAL_QUADPLANE_ENABLED + case AUX_FUNC::ARMDISARM_AIRMODE: + RC_Channel::do_aux_function_armdisarm(ch_flag); + if (plane.arming.is_armed()) { + plane.quadplane.air_mode = AirMode::ON; + } + break; +#endif default: return RC_Channel::do_aux_function(ch_option, ch_flag); diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index ea26722620..65124c7d21 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -36,7 +36,11 @@ void Plane::init_ardupilot() // initialise rc channels including setting mode rc().init(); +#if HAL_QUADPLANE_ENABLED rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, (quadplane.enabled() && (quadplane.options & QuadPlane::OPTION_AIRMODE_UNUSED) && (rc().find_channel_for_option(RC_Channel::AUX_FUNC::AIRMODE) == nullptr)) ? RC_Channel::AUX_FUNC::ARMDISARM_AIRMODE : RC_Channel::AUX_FUNC::ARMDISARM); +#else + rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM); +#endif relay.init();