mirror of https://github.com/ArduPilot/ardupilot
AP_RangeFinder: fixed cm to meter comparison
thanks to EShamaev for this fix (see PR #1352)
This commit is contained in:
parent
75c9689a64
commit
4c4a4f9ea5
|
@ -107,8 +107,8 @@ void AP_RangeFinder_analog::update(void)
|
|||
dist_m = 0;
|
||||
}
|
||||
dist_m = scaling / (v - offset);
|
||||
if (isinf(dist_m) || dist_m > max_distance_cm) {
|
||||
dist_m = max_distance_cm * 0.01;
|
||||
if (isinf(dist_m) || dist_m > max_distance_cm * 0.01f) {
|
||||
dist_m = max_distance_cm * 0.01f;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue