From 5db60eb9ac32dc97d75758a830da519fd9529d5e Mon Sep 17 00:00:00 2001 From: rishabsingh3003 Date: Sun, 22 Oct 2023 15:31:51 -0400 Subject: [PATCH] AP_RangeFinder: Allow new Maxsonar I2C reading even if reading fails --- libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp index ed6e1d722f..1cb7cdc5af 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp @@ -116,11 +116,11 @@ bool AP_RangeFinder_MaxsonarI2CXL::get_reading(uint16_t &reading_cm) if (ret) { // combine results into distance reading_cm = be16toh(val); - - // trigger a new reading - start_reading(); } + // trigger a new reading + start_reading(); + return ret; }