mavlink: set signal_quality (and sane variance)

Otherwise this distance data is actually not used at all.
This commit is contained in:
Julian Oes 2021-09-09 17:40:00 +02:00 committed by Daniel Agar
parent aefbd80b53
commit dd00e43ca3
1 changed files with 4 additions and 2 deletions

View File

@ -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);
}