From ffe854063b1882058a1ebd5cadd4f12bb972f113 Mon Sep 17 00:00:00 2001 From: "pierre-louis.k" Date: Fri, 3 Aug 2018 16:42:52 +0200 Subject: [PATCH] AP_RangeFinder: Remove range enforcement on out of range --- .../AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp index e6ddc93201..3d654a4a87 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp @@ -125,8 +125,8 @@ bool AP_RangeFinder_TeraRangerI2C::collect_raw(uint16_t &raw_distance) if (d[2] != crc_crc8(d, 2)) { return false; } else { - raw_distance = ((uint16_t(d[0]) << 8) | d[1]); - return true; + raw_distance = ((uint16_t(d[0]) << 8) | d[1]); + return true; } } @@ -135,11 +135,12 @@ bool AP_RangeFinder_TeraRangerI2C::process_raw_measure(uint16_t raw_distance, ui { // Check for error codes if (raw_distance == 0xFFFF) { - // Too far away + // Too far away is unreliable so we dont enforce max range here return false; } else if (raw_distance == 0x0000) { // Too close - return false; + output_distance_cm = state.min_distance_cm; + return true; } else if (raw_distance == 0x0001) { // Unable to measure return false;