diff --git a/Rover/RC_Channel.cpp b/Rover/RC_Channel.cpp index 9a89b66d61..eba8533119 100644 --- a/Rover/RC_Channel.cpp +++ b/Rover/RC_Channel.cpp @@ -26,7 +26,7 @@ void RC_Channel_Rover::mode_switch_changed(modeswitch_pos_t new_pos) } // 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 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) { case AUX_FUNC::DO_NOTHING: diff --git a/Rover/RC_Channel.h b/Rover/RC_Channel.h index d25d714aa2..01c83da59b 100644 --- a/Rover/RC_Channel.h +++ b/Rover/RC_Channel.h @@ -11,8 +11,8 @@ public: protected: - void init_aux_function(aux_func_t ch_option, AuxSwitchPos) override; - bool do_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 ch_option, AuxSwitchPos) override; // called when the mode switch changes position: void mode_switch_changed(modeswitch_pos_t new_pos) override;