mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
RC_Channel: add get_channel_pos function
This commit is contained in:
parent
de854a2ffe
commit
806bd38c7f
@ -997,6 +997,14 @@ RC_Channel::aux_switch_pos_t RC_Channel::get_aux_switch_pos() const
|
|||||||
return position;
|
return position;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// return switch position value as LOW, MIDDLE, HIGH
|
||||||
|
// if reading the switch fails then it returns LOW
|
||||||
|
RC_Channel::aux_switch_pos_t 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::aux_switch_pos_t::LOW;
|
||||||
|
}
|
||||||
|
|
||||||
RC_Channel *RC_Channels::find_channel_for_option(const RC_Channel::aux_func_t option)
|
RC_Channel *RC_Channels::find_channel_for_option(const RC_Channel::aux_func_t option)
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
|
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
|
||||||
|
@ -324,6 +324,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::aux_switch_pos_t get_channel_pos(const uint8_t rcmapchan) const;
|
||||||
|
|
||||||
void init_aux_all();
|
void init_aux_all();
|
||||||
void read_aux_all();
|
void read_aux_all();
|
||||||
|
Loading…
Reference in New Issue
Block a user