From dd769c2c6dd0b43005eb428070e0848ab642a475 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 12 Sep 2024 14:06:07 +1000 Subject: [PATCH] RC_Channel: remove unused get_channel_pos method --- libraries/RC_Channel/RC_Channel.cpp | 8 -------- libraries/RC_Channel/RC_Channel.h | 1 - 2 files changed, 9 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 2722464df5666..0888c0e939b46 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -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