From 67bdec3325869f811c803ee7e8baa6a69d735dca Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Wed, 3 Feb 2021 18:21:39 +0100 Subject: [PATCH] AP_OSD: use AUX_PWM_TRIGGER_LOW and AUX_PWM_TRIGGER_HIGH --- libraries/AP_OSD/AP_OSD_ParamScreen.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_OSD/AP_OSD_ParamScreen.cpp b/libraries/AP_OSD/AP_OSD_ParamScreen.cpp index cd265bbb3e..58f6529511 100644 --- a/libraries/AP_OSD/AP_OSD_ParamScreen.cpp +++ b/libraries/AP_OSD/AP_OSD_ParamScreen.cpp @@ -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;