mirror of https://github.com/ArduPilot/ardupilot
Copter: support ARMDISARM_AIRMODE
This commit is contained in:
parent
db416bbeef
commit
07824fc963
|
@ -101,6 +101,7 @@ void RC_Channel_Copter::init_aux_function(const aux_func_t ch_option, const AuxS
|
|||
case AUX_FUNC::AUTO_RTL:
|
||||
case AUX_FUNC::TURTLE:
|
||||
case AUX_FUNC::SIMPLE_HEADING_RESET:
|
||||
case AUX_FUNC::ARMDISARM_AIRMODE:
|
||||
break;
|
||||
case AUX_FUNC::ACRO_TRAINER:
|
||||
case AUX_FUNC::ATTCON_ACCEL_LIM:
|
||||
|
@ -145,16 +146,6 @@ void RC_Channel_Copter::do_aux_function_change_mode(const Mode::Number mode,
|
|||
}
|
||||
}
|
||||
|
||||
void RC_Channel_Copter::do_aux_function_armdisarm(const AuxSwitchPos ch_flag)
|
||||
{
|
||||
RC_Channel::do_aux_function_armdisarm(ch_flag);
|
||||
if (copter.arming.is_armed()) {
|
||||
// remember that we are using an arming switch, for use by
|
||||
// set_throttle_zero_flag
|
||||
copter.ap.armed_with_switch = true;
|
||||
}
|
||||
}
|
||||
|
||||
// do_aux_function - implement the function invoked by auxiliary switches
|
||||
bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag)
|
||||
{
|
||||
|
@ -593,6 +584,13 @@ bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi
|
|||
}
|
||||
break;
|
||||
|
||||
case AUX_FUNC::ARMDISARM_AIRMODE:
|
||||
RC_Channel::do_aux_function_armdisarm(ch_flag);
|
||||
if (copter.arming.is_armed()) {
|
||||
copter.ap.armed_with_airmode_switch = true;
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
return RC_Channel::do_aux_function(ch_option, ch_flag);
|
||||
}
|
||||
|
|
|
@ -16,7 +16,6 @@ protected:
|
|||
|
||||
private:
|
||||
|
||||
void do_aux_function_armdisarm(const AuxSwitchPos ch_flag) override;
|
||||
void do_aux_function_change_mode(const Mode::Number mode,
|
||||
const AuxSwitchPos ch_flag);
|
||||
void do_aux_function_change_air_mode(const AuxSwitchPos ch_flag);
|
||||
|
|
Loading…
Reference in New Issue