AP_RangeFinder: a to close reading is not the minimum distance

This commit is contained in:
Michael du Breuil 2020-01-24 17:27:41 -07:00 committed by Andrew Tridgell
parent 8b20c82a18
commit 7bc1f4ff9b

View File

@ -143,8 +143,7 @@ bool AP_RangeFinder_TeraRangerI2C::process_raw_measure(uint16_t raw_distance, ui
return false; return false;
} else if (raw_distance == 0x0000) { } else if (raw_distance == 0x0000) {
// Too close // Too close
output_distance_cm = params.min_distance_cm; return false;
return true;
} else if (raw_distance == 0x0001) { } else if (raw_distance == 0x0001) {
// Unable to measure // Unable to measure
return false; return false;