mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Channel rage fix - low output was always 0 vs _low
This commit is contained in:
parent
bafb478924
commit
00cabc6343
@ -246,7 +246,7 @@ RC_Channel::pwm_to_range()
|
|||||||
if(radio_in > radio_trim_low)
|
if(radio_in > radio_trim_low)
|
||||||
return (_low + ((long)(_high - _low) * (long)(radio_in - radio_trim_low)) / (long)(radio_max - radio_trim_low));
|
return (_low + ((long)(_high - _low) * (long)(radio_in - radio_trim_low)) / (long)(radio_max - radio_trim_low));
|
||||||
else
|
else
|
||||||
return 0;
|
return _low;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user