Browse Source

RangeFinder: remove divide-by-zero possibility

mission-4.1.18
Peter Barker 7 years ago committed by Randy Mackay
parent
commit
c627ed6ae3
  1. 3
      libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp

3
libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp

@ -104,8 +104,9 @@ void AP_RangeFinder_analog::update(void) @@ -104,8 +104,9 @@ void AP_RangeFinder_analog::update(void)
case RangeFinder::FUNCTION_HYPERBOLA:
if (v <= offset) {
dist_m = 0;
} else {
dist_m = scaling / (v - offset);
}
dist_m = scaling / (v - offset);
if (isinf(dist_m) || dist_m > _max_distance_cm * 0.01f) {
dist_m = _max_distance_cm * 0.01f;
}

Loading…
Cancel
Save