mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_OSD: use AUX_PWM_TRIGGER_LOW and AUX_PWM_TRIGGER_HIGH
This commit is contained in:
parent
9362039feb
commit
67bdec3325
@ -406,9 +406,9 @@ 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();
|
||||
|
||||
if (in < 1300) {
|
||||
if (in < RC_Channel::AUX_PWM_TRIGGER_LOW) {
|
||||
return switch_reversed ? RC_Channel::AuxSwitchPos::HIGH : RC_Channel::AuxSwitchPos::LOW;
|
||||
} else if (in > 1700) {
|
||||
} else if (in > RC_Channel::AUX_PWM_TRIGGER_HIGH) {
|
||||
return switch_reversed ? RC_Channel::AuxSwitchPos::LOW : RC_Channel::AuxSwitchPos::HIGH;
|
||||
} else {
|
||||
return RC_Channel::AuxSwitchPos::MIDDLE;
|
||||
|
Loading…
Reference in New Issue
Block a user