RC_Channel: remove unused method get_channel_pos

This commit is contained in:
Peter Barker 2024-11-13 12:20:08 +11:00 committed by Andrew Tridgell
parent dce4396430
commit 88a80993dc
2 changed files with 0 additions and 9 deletions

View File

@ -1921,14 +1921,6 @@ RC_Channel::AuxSwitchPos RC_Channel::get_aux_switch_pos() const
return position;
}
// return switch position value as LOW, MIDDLE, HIGH
// if reading the switch fails then it returns LOW
RC_Channel::AuxSwitchPos RC_Channels::get_channel_pos(const uint8_t rcmapchan) const
{
const RC_Channel* chan = rc().channel(rcmapchan-1);
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 option)
{
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {

View File

@ -504,7 +504,6 @@ public:
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 old_option, const RC_Channel::AUX_FUNC new_option);
void init_aux_all();