5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-05 15:38:29 -04:00

RangeFinder: remove divide-by-zero possibility

This commit is contained in:
Peter Barker 2018-03-31 16:25:03 +11:00 committed by Randy Mackay
parent f383cf91a2
commit c627ed6ae3

View File

@ -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;
}