diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 14343a13b5..2dec9bb090 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -1268,3 +1268,18 @@ bool RC_Channels::duplicate_options_exist() } return false; } + +// 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) +{ + for (uint8_t i=0; ioption.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 d974a661e1..acb6e27963 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -426,6 +426,7 @@ public: class RC_Channel *find_channel_for_option(const RC_Channel::aux_func_t 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 init_aux_all(); void read_aux_all();