mirror of https://github.com/ArduPilot/ardupilot
Rover: use AUX_FUNC instead of typedef aux_func_t
This commit is contained in:
parent
482c8d7f0b
commit
4b5553ac33
|
@ -26,7 +26,7 @@ void RC_Channel_Rover::mode_switch_changed(modeswitch_pos_t new_pos)
|
||||||
}
|
}
|
||||||
|
|
||||||
// init_aux_switch_function - initialize aux functions
|
// init_aux_switch_function - initialize aux functions
|
||||||
void RC_Channel_Rover::init_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag)
|
void RC_Channel_Rover::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag)
|
||||||
{
|
{
|
||||||
// init channel options
|
// init channel options
|
||||||
switch (ch_option) {
|
switch (ch_option) {
|
||||||
|
@ -130,7 +130,7 @@ void RC_Channel_Rover::do_aux_function_sailboat_motor_3pos(const AuxSwitchPos ch
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
bool RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag)
|
bool RC_Channel_Rover::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag)
|
||||||
{
|
{
|
||||||
switch (ch_option) {
|
switch (ch_option) {
|
||||||
case AUX_FUNC::DO_NOTHING:
|
case AUX_FUNC::DO_NOTHING:
|
||||||
|
|
|
@ -11,8 +11,8 @@ public:
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
void init_aux_function(aux_func_t ch_option, AuxSwitchPos) override;
|
void init_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override;
|
||||||
bool do_aux_function(aux_func_t ch_option, AuxSwitchPos) override;
|
bool do_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override;
|
||||||
|
|
||||||
// called when the mode switch changes position:
|
// called when the mode switch changes position:
|
||||||
void mode_switch_changed(modeswitch_pos_t new_pos) override;
|
void mode_switch_changed(modeswitch_pos_t new_pos) override;
|
||||||
|
|
Loading…
Reference in New Issue