mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
SRV_Channel: handle reversed channels in limit PWMs
This commit is contained in:
parent
f22d5f0d40
commit
4314d0ea12
@ -172,9 +172,9 @@ uint16_t SRV_Channel::get_limit_pwm(LimitValue limit) const
|
|||||||
case SRV_CHANNEL_LIMIT_TRIM:
|
case SRV_CHANNEL_LIMIT_TRIM:
|
||||||
return servo_trim;
|
return servo_trim;
|
||||||
case SRV_CHANNEL_LIMIT_MIN:
|
case SRV_CHANNEL_LIMIT_MIN:
|
||||||
return servo_min;
|
return reversed?servo_max:servo_min;
|
||||||
case SRV_CHANNEL_LIMIT_MAX:
|
case SRV_CHANNEL_LIMIT_MAX:
|
||||||
return servo_max;
|
return reversed?servo_min:servo_max;
|
||||||
case SRV_CHANNEL_LIMIT_ZERO_PWM:
|
case SRV_CHANNEL_LIMIT_ZERO_PWM:
|
||||||
default:
|
default:
|
||||||
return 0;
|
return 0;
|
||||||
|
Loading…
Reference in New Issue
Block a user