mirror of https://github.com/ArduPilot/ardupilot
Rover: move to AuxFuncTrigger structure
This commit is contained in:
parent
496cbd7ead
commit
858d57f0aa
|
@ -130,8 +130,11 @@ void RC_Channel_Rover::do_aux_function_sailboat_motor_3pos(const AuxSwitchPos ch
|
|||
}
|
||||
}
|
||||
|
||||
bool RC_Channel_Rover::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag)
|
||||
bool RC_Channel_Rover::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::DO_NOTHING:
|
||||
break;
|
||||
|
@ -261,7 +264,7 @@ bool RC_Channel_Rover::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch
|
|||
break;
|
||||
|
||||
default:
|
||||
return RC_Channel::do_aux_function(ch_option, ch_flag);
|
||||
return RC_Channel::do_aux_function(trigger);
|
||||
|
||||
}
|
||||
|
||||
|
|
|
@ -12,7 +12,7 @@ public:
|
|||
protected:
|
||||
|
||||
void init_aux_function(AUX_FUNC ch_option, AuxSwitchPos) 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