mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_OSD: remove intermediate option_is_enabled methods for RC_Channel
This commit is contained in:
parent
6255ecbfce
commit
53b99dd17a
@ -405,7 +405,7 @@ RC_Channel::AuxSwitchPos AP_OSD_ParamScreen::get_channel_pos(uint8_t rcmapchan)
|
||||
}
|
||||
|
||||
// switch is reversed if 'reversed' option set on channel and switches reverse is allowed by RC_OPTIONS
|
||||
bool switch_reversed = chan->get_reverse() && rc().switch_reverse_allowed();
|
||||
bool switch_reversed = chan->get_reverse() && rc().option_is_enabled(RC_Channels::Option::ALLOW_SWITCH_REV);
|
||||
|
||||
if (in < RC_Channel::AUX_PWM_TRIGGER_LOW) {
|
||||
return switch_reversed ? RC_Channel::AuxSwitchPos::HIGH : RC_Channel::AuxSwitchPos::LOW;
|
||||
|
Loading…
Reference in New Issue
Block a user