From 7bc1f4ff9b3f52d33fb115b349828e8fac48f5b6 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Fri, 24 Jan 2020 17:27:41 -0700 Subject: [PATCH] AP_RangeFinder: a to close reading is not the minimum distance --- libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp index 0a4220f2b4..911823e5bb 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp @@ -143,8 +143,7 @@ bool AP_RangeFinder_TeraRangerI2C::process_raw_measure(uint16_t raw_distance, ui return false; } else if (raw_distance == 0x0000) { // Too close - output_distance_cm = params.min_distance_cm; - return true; + return false; } else if (raw_distance == 0x0001) { // Unable to measure return false;