mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ArduPlane: move to AuxFuncTrigger structure
This commit is contained in:
parent
0ca5695cb7
commit
f7c4320e86
@ -194,7 +194,7 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option,
|
||||
#if AP_ICENGINE_ENABLED
|
||||
case AUX_FUNC::ICE_START_STOP:
|
||||
#endif
|
||||
run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT);
|
||||
run_aux_function(ch_option, ch_flag, AuxFuncTrigger::Source::INIT);
|
||||
break;
|
||||
|
||||
case AUX_FUNC::REVERSE_THROTTLE:
|
||||
@ -216,8 +216,11 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option,
|
||||
}
|
||||
|
||||
// do_aux_function - implement the function invoked by auxiliary switches
|
||||
bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag)
|
||||
bool RC_Channel_Plane::do_aux_function(const AuxFuncTrigger &trigger)
|
||||
{
|
||||
const AUX_FUNC &ch_option = trigger.func;
|
||||
const AuxSwitchPos &ch_flag = trigger.pos;
|
||||
|
||||
switch(ch_option) {
|
||||
case AUX_FUNC::INVERTED:
|
||||
plane.inverted_flight = (ch_flag == AuxSwitchPos::HIGH);
|
||||
@ -472,7 +475,7 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch
|
||||
#endif
|
||||
|
||||
default:
|
||||
return RC_Channel::do_aux_function(ch_option, ch_flag);
|
||||
return RC_Channel::do_aux_function(trigger);
|
||||
}
|
||||
|
||||
return true;
|
||||
|
@ -11,7 +11,7 @@ protected:
|
||||
|
||||
void init_aux_function(AUX_FUNC ch_option,
|
||||
AuxSwitchPos ch_flag) override;
|
||||
bool do_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override;
|
||||
bool do_aux_function(const AuxFuncTrigger &trigger) override;
|
||||
|
||||
// called when the mode switch changes position:
|
||||
void mode_switch_changed(modeswitch_pos_t new_pos) override;
|
||||
|
Loading…
Reference in New Issue
Block a user