mirror of https://github.com/ArduPilot/ardupilot
prevent div by 0
This commit is contained in:
parent
3f3c04f95b
commit
d18bb1cc7e
|
@ -191,6 +191,10 @@ RC_Channel::pwm_to_angle()
|
|||
int radio_trim_high = radio_trim + _dead_zone;
|
||||
int radio_trim_low = radio_trim - _dead_zone;
|
||||
|
||||
// prevent div by 0
|
||||
if ((radio_trim_low - radio_min) == 0 || (radio_max - radio_trim_high) == 0)
|
||||
return 0;
|
||||
|
||||
if(radio_in > radio_trim_high){
|
||||
return _reverse * ((long)_high * (long)(radio_in - radio_trim_high)) / (long)(radio_max - radio_trim_high);
|
||||
}else if(radio_in < radio_trim_low){
|
||||
|
|
Loading…
Reference in New Issue