From e53f2466b497458c5089455e9735945702a9952c Mon Sep 17 00:00:00 2001 From: Clyde McQueen Date: Tue, 18 Jul 2023 13:19:38 -0700 Subject: [PATCH] Ignore DISTANCE_SENSOR msgs with low signal_quality --- libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp | 9 +++++---- libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h | 1 + 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp index 5e52a9a2223bc8..16da6d5f5f2299 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp @@ -27,13 +27,14 @@ void AP_RangeFinder_MAVLink::handle_msg(const mavlink_message_t &msg) mavlink_distance_sensor_t packet; mavlink_msg_distance_sensor_decode(&msg, &packet); - // only accept distances for the configured orentation + // only accept distances for the configured orientation if (packet.orientation == orientation()) { state.last_reading_ms = AP_HAL::millis(); distance_cm = packet.current_distance; _max_distance_cm = packet.max_distance; _min_distance_cm = packet.min_distance; sensor_type = (MAV_DISTANCE_SENSOR)packet.type; + signal_quality = packet.signal_quality; } } @@ -66,9 +67,9 @@ int16_t AP_RangeFinder_MAVLink::min_distance_cm() const */ void AP_RangeFinder_MAVLink::update(void) { - //Time out on incoming data; if we don't get new - //data in 500ms, dump it - if (AP_HAL::millis() - state.last_reading_ms > AP_RANGEFINDER_MAVLINK_TIMEOUT_MS) { + // time out on incoming data; if we don't get new data in 500ms, dump it + // ignore readings where signal_quality is below cutoff + if (AP_HAL::millis() - state.last_reading_ms > AP_RANGEFINDER_MAVLINK_TIMEOUT_MS || (signal_quality > 0 && signal_quality < 90)) { set_status(RangeFinder::Status::NoData); state.distance_m = 0.0f; } else { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h index b38c6fcc494750..4012d87a0be435 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h @@ -43,6 +43,7 @@ class AP_RangeFinder_MAVLink : public AP_RangeFinder_Backend uint16_t distance_cm; uint16_t _max_distance_cm; uint16_t _min_distance_cm; + uint8_t signal_quality; // start a reading static bool start_reading(void);