mirror of https://github.com/ArduPilot/ardupilot
Issue 416: RC_Channel – Fix to make dead_zones still output 0
This commit is contained in:
parent
1c690b44de
commit
0adb5cb396
|
@ -247,6 +247,8 @@ 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 if(_dead_zone > 0)
|
||||||
|
return 0;
|
||||||
else
|
else
|
||||||
return _low;
|
return _low;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue