From 4314d0ea12a563fd951b1cd34446da1792e3a56d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 13 Sep 2018 06:22:45 +1000 Subject: [PATCH] SRV_Channel: handle reversed channels in limit PWMs --- libraries/SRV_Channel/SRV_Channel.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/SRV_Channel/SRV_Channel.cpp b/libraries/SRV_Channel/SRV_Channel.cpp index 1e059dc420..78f2db2121 100644 --- a/libraries/SRV_Channel/SRV_Channel.cpp +++ b/libraries/SRV_Channel/SRV_Channel.cpp @@ -172,9 +172,9 @@ uint16_t SRV_Channel::get_limit_pwm(LimitValue limit) const case SRV_CHANNEL_LIMIT_TRIM: return servo_trim; case SRV_CHANNEL_LIMIT_MIN: - return servo_min; + return reversed?servo_max:servo_min; case SRV_CHANNEL_LIMIT_MAX: - return servo_max; + return reversed?servo_min:servo_max; case SRV_CHANNEL_LIMIT_ZERO_PWM: default: return 0;