SRV_Channel: handle reversed channels in limit PWMs

This commit is contained in:
Andrew Tridgell 2018-09-13 06:22:45 +10:00
parent f22d5f0d40
commit 4314d0ea12

View File

@ -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;