diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index 3fa2f6c4d8..5c4c79c769 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -108,6 +108,7 @@ void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwi case AUX_FUNC::SIMPLE_HEADING_RESET: case AUX_FUNC::ARMDISARM_AIRMODE: case AUX_FUNC::TURBINE_START: + case AUX_FUNC::FLIGHTMODE_PAUSE: break; case AUX_FUNC::ACRO_TRAINER: case AUX_FUNC::ATTCON_ACCEL_LIM: @@ -566,6 +567,21 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc } break; + case AUX_FUNC::FLIGHTMODE_PAUSE: + switch (ch_flag) { + case AuxSwitchPos::HIGH: + if (!copter.flightmode->pause()) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Flight Mode Pause failed"); + } + break; + case AuxSwitchPos::MIDDLE: + break; + case AuxSwitchPos::LOW: + copter.flightmode->resume(); + break; + } + break; + case AUX_FUNC::ZIGZAG_Auto: #if MODE_ZIGZAG_ENABLED == ENABLED if (copter.flightmode == &copter.mode_zigzag) {