From 0d3c00cb9628c3e7abc602c5e439827751a52a8f Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 30 Aug 2021 15:27:41 +0100 Subject: [PATCH] AP_Rangefinder: MAVLink: accept data only from configured orentation --- libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp index c0c78871b8..cbae721d22 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp @@ -24,8 +24,8 @@ 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 downward facing sensors - if (packet.orientation == MAV_SENSOR_ROTATION_PITCH_270) { + // only accept distances for the configured orentation + if (packet.orientation == orientation()) { state.last_reading_ms = AP_HAL::millis(); distance_cm = packet.current_distance; _max_distance_cm = packet.max_distance;