From 8de103d6eee44f0a56a5cb2ded92667cf2bda924 Mon Sep 17 00:00:00 2001 From: muramura Date: Sat, 23 Mar 2024 23:32:46 +0900 Subject: [PATCH] AP_RangeFinder: Move the flag setting location of has_data --- libraries/AP_RangeFinder/AP_RangeFinder_Ainstein_LR_D1.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Ainstein_LR_D1.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Ainstein_LR_D1.cpp index 3e18c96bbe..775a004268 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Ainstein_LR_D1.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Ainstein_LR_D1.cpp @@ -71,8 +71,6 @@ bool AP_RangeFinder_Ainstein_LR_D1::get_reading(float &reading_m) reading_m = UINT16_VALUE(buffer[3], buffer[4]) * 0.01; const uint8_t snr = buffer[5]; - has_data = true; - #if AP_RANGEFINDER_AINSTEIN_LR_D1_SHOW_MALFUNCTIONS const uint32_t now_ms = AP_HAL::millis(); if (malfunction_alert_prev != malfunction_alert && now_ms - malfunction_alert_last_send_ms >= 1000) { @@ -102,6 +100,7 @@ bool AP_RangeFinder_Ainstein_LR_D1::get_reading(float &reading_m) state.status = RangeFinder::Status::NoData; } } else { + has_data = true; state.status = RangeFinder::Status::Good; } }