mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: remove unused method get_channel_pos
This commit is contained in:
parent
dce4396430
commit
88a80993dc
|
@ -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++) {
|
||||
|
|
|
@ -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();
|
||||
|
|
Loading…
Reference in New Issue