From ad3724177dc8c61c1baa8debbec64ffd877e90e7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 14 Feb 2024 13:36:11 +1100 Subject: [PATCH] RC_Channel: use AUX_FUNC instead of typedef aux_func_t --- libraries/RC_Channel/RC_Channel.cpp | 18 +++++++++--------- libraries/RC_Channel/RC_Channel.h | 15 +++++++-------- libraries/RC_Channel/RC_Channels.cpp | 6 +++--- 3 files changed, 19 insertions(+), 20 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 736e7e18d6..a544f8638e 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -617,7 +617,7 @@ bool RC_Channel::debounce_completed(int8_t position) // // init_aux_switch_function - initialize aux functions -void RC_Channel::init_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag) +void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag) { // init channel options switch (ch_option) { @@ -805,7 +805,7 @@ const char *RC_Channel::string_for_aux_pos(AuxSwitchPos pos) const */ bool RC_Channel::read_aux() { - const aux_func_t _option = (aux_func_t)option.get(); + const AUX_FUNC _option = (AUX_FUNC)option.get(); if (_option == AUX_FUNC::DO_NOTHING) { // may wish to add special cases for other "AUXSW" things // here e.g. RCMAP_ROLL etc once they become options @@ -1214,7 +1214,7 @@ void RC_Channel::do_aux_function_fft_notch_tune(const AuxSwitchPos ch_flag) #endif } -bool RC_Channel::run_aux_function(aux_func_t ch_option, AuxSwitchPos pos, AuxFuncTriggerSource source) +bool RC_Channel::run_aux_function(AUX_FUNC ch_option, AuxSwitchPos pos, AuxFuncTriggerSource source) { #if AP_SCRIPTING_ENABLED rc().set_aux_cached(ch_option, pos); @@ -1249,7 +1249,7 @@ bool RC_Channel::run_aux_function(aux_func_t ch_option, AuxSwitchPos pos, AuxFun return ret; } -bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag) +bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag) { switch (ch_option) { #if AP_FENCE_ENABLED @@ -1684,7 +1684,7 @@ void RC_Channel::init_aux() if (!read_3pos_switch(position)) { position = AuxSwitchPos::LOW; } - init_aux_function((aux_func_t)option.get(), position); + init_aux_function((AUX_FUNC)option.get(), position); } // read_3pos_switch @@ -1726,7 +1726,7 @@ RC_Channel::AuxSwitchPos RC_Channels::get_channel_pos(const uint8_t rcmapchan) c return chan != nullptr ? chan->get_aux_switch_pos() : RC_Channel::AuxSwitchPos::LOW; } -RC_Channel *RC_Channels::find_channel_for_option(const RC_Channel::aux_func_t option) +RC_Channel *RC_Channels::find_channel_for_option(const RC_Channel::AUX_FUNC option) { for (uint8_t i=0; ioption.get() == option) { + if ((RC_Channel::AUX_FUNC)c->option.get() == option) { return c; } } @@ -1770,7 +1770,7 @@ bool RC_Channels::duplicate_options_exist() } // convert option parameter from old to new -void RC_Channels::convert_options(const RC_Channel::aux_func_t old_option, const RC_Channel::aux_func_t new_option) +void RC_Channels::convert_options(const RC_Channel::AUX_FUNC old_option, const RC_Channel::AUX_FUNC new_option) { for (uint8_t i=0; ioption.get() == old_option) { + if ((RC_Channel::AUX_FUNC)c->option.get() == old_option) { c->option.set_and_save((int16_t)new_option); } } diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 368e3a013e..4ad9e532fa 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -285,7 +285,6 @@ public: // this must be higher than any aux function above AUX_FUNCTION_MAX = 308, }; - typedef enum AUX_FUNC aux_func_t; // auxiliary switch handling (n.b.: we store this as 2-bits!): enum class AuxSwitchPos : uint8_t { @@ -306,7 +305,7 @@ public: AuxSwitchPos get_aux_switch_pos() const; // wrapper function around do_aux_function which allows us to log - bool run_aux_function(aux_func_t ch_option, AuxSwitchPos pos, AuxFuncTriggerSource source); + bool run_aux_function(AUX_FUNC ch_option, AuxSwitchPos pos, AuxFuncTriggerSource source); #if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED const char *string_for_aux_function(AUX_FUNC function) const; @@ -334,10 +333,10 @@ public: protected: - virtual void init_aux_function(aux_func_t ch_option, AuxSwitchPos); + virtual void init_aux_function(AUX_FUNC ch_option, AuxSwitchPos); // virtual function to be overridden my subclasses - virtual bool do_aux_function(aux_func_t ch_option, AuxSwitchPos); + virtual bool do_aux_function(AUX_FUNC ch_option, AuxSwitchPos); void do_aux_function_armdisarm(const AuxSwitchPos ch_flag); void do_aux_function_avoid_adsb(const AuxSwitchPos ch_flag); @@ -482,10 +481,10 @@ public: // is RC channel 1. Beware this is not a cheap call. uint16_t get_override_mask() const; - class RC_Channel *find_channel_for_option(const RC_Channel::aux_func_t option); + class RC_Channel *find_channel_for_option(const RC_Channel::AUX_FUNC option); bool duplicate_options_exist(); RC_Channel::AuxSwitchPos get_channel_pos(const uint8_t rcmapchan) const; - void convert_options(const RC_Channel::aux_func_t old_option, const RC_Channel::aux_func_t new_option); + void convert_options(const RC_Channel::AUX_FUNC old_option, const RC_Channel::AUX_FUNC new_option); void init_aux_all(); void read_aux_all(); @@ -586,7 +585,7 @@ public: #if AP_SCRIPTING_ENABLED // get last aux cached value for scripting. Returns false if never set, otherwise 0,1,2 - bool get_aux_cached(RC_Channel::aux_func_t aux_fn, uint8_t &pos); + bool get_aux_cached(RC_Channel::AUX_FUNC aux_fn, uint8_t &pos); #endif // returns true if we've ever seen RC input, via overrides or via @@ -637,7 +636,7 @@ private: HAL_Semaphore aux_cache_sem; Bitmask aux_cached; - void set_aux_cached(RC_Channel::aux_func_t aux_fn, RC_Channel::AuxSwitchPos pos); + void set_aux_cached(RC_Channel::AUX_FUNC aux_fn, RC_Channel::AuxSwitchPos pos); #endif }; diff --git a/libraries/RC_Channel/RC_Channels.cpp b/libraries/RC_Channel/RC_Channels.cpp index 4beee5e5d6..9ec73c5dab 100644 --- a/libraries/RC_Channel/RC_Channels.cpp +++ b/libraries/RC_Channel/RC_Channels.cpp @@ -236,7 +236,7 @@ bool RC_Channels::flight_mode_channel_conflicts_with_rc_option() const if (chan == nullptr) { return false; } - return (RC_Channel::aux_func_t)chan->option.get() != RC_Channel::AUX_FUNC::DO_NOTHING; + return (RC_Channel::AUX_FUNC)chan->option.get() != RC_Channel::AUX_FUNC::DO_NOTHING; } /* @@ -276,7 +276,7 @@ uint32_t RC_Channels::enabled_protocols() const /* get last aux cached value for scripting. Returns false if never set, otherwise 0,1,2 */ -bool RC_Channels::get_aux_cached(RC_Channel::aux_func_t aux_fn, uint8_t &pos) +bool RC_Channels::get_aux_cached(RC_Channel::AUX_FUNC aux_fn, uint8_t &pos) { const uint16_t aux_idx = uint16_t(aux_fn); if (aux_idx >= unsigned(RC_Channel::AUX_FUNC::AUX_FUNCTION_MAX)) { @@ -295,7 +295,7 @@ bool RC_Channels::get_aux_cached(RC_Channel::aux_func_t aux_fn, uint8_t &pos) /* set cached value of an aux function */ -void RC_Channels::set_aux_cached(RC_Channel::aux_func_t aux_fn, RC_Channel::AuxSwitchPos pos) +void RC_Channels::set_aux_cached(RC_Channel::AUX_FUNC aux_fn, RC_Channel::AuxSwitchPos pos) { const uint16_t aux_idx = uint16_t(aux_fn); if (aux_idx < unsigned(RC_Channel::AUX_FUNC::AUX_FUNCTION_MAX)) {