mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
RC_Channel: add convert_options function
This commit is contained in:
parent
c67705b02d
commit
524ea39dfa
@ -1268,3 +1268,18 @@ bool RC_Channels::duplicate_options_exist()
|
|||||||
}
|
}
|
||||||
return false;
|
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; i<NUM_RC_CHANNELS; i++) {
|
||||||
|
RC_Channel *c = channel(i);
|
||||||
|
if (c == nullptr) {
|
||||||
|
// odd?
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
if ((RC_Channel::aux_func_t)c->option.get() == old_option) {
|
||||||
|
c->option.set_and_save((int16_t)new_option);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
@ -426,6 +426,7 @@ public:
|
|||||||
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_t option);
|
||||||
bool duplicate_options_exist();
|
bool duplicate_options_exist();
|
||||||
RC_Channel::AuxSwitchPos get_channel_pos(const uint8_t rcmapchan) const;
|
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 init_aux_all();
|
||||||
void read_aux_all();
|
void read_aux_all();
|
||||||
|
Loading…
Reference in New Issue
Block a user