From dd00e43ca31945ffa4be0863a532bae1de8c217e Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 9 Sep 2021 17:40:00 +0200 Subject: [PATCH] mavlink: set signal_quality (and sane variance) Otherwise this distance data is actually not used at all. --- src/modules/mavlink/mavlink_receiver.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 713e2dc9d5..afcced5eef 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -835,7 +835,8 @@ MavlinkReceiver::handle_message_optical_flow_rad(mavlink_message_t *msg) d.type = distance_sensor_s::MAV_DISTANCE_SENSOR_ULTRASOUND; d.device_id = device_id.devid; d.orientation = distance_sensor_s::ROTATION_DOWNWARD_FACING; - d.variance = 0.0; + d.variance = 0.01; + d.signal_quality = -1; _flow_distance_sensor_pub.publish(d); } @@ -880,7 +881,8 @@ MavlinkReceiver::handle_message_hil_optical_flow(mavlink_message_t *msg) d.type = distance_sensor_s::MAV_DISTANCE_SENSOR_LASER; d.device_id = device_id.devid; d.orientation = distance_sensor_s::ROTATION_DOWNWARD_FACING; - d.variance = 0.0; + d.variance = 0.01; + d.signal_quality = -1; _flow_distance_sensor_pub.publish(d); }