From f9324fb76a4af1e2cfe8813e1a7af5d65c2b1ed1 Mon Sep 17 00:00:00 2001
From: Gabriel Moreno <gabrielm@cs.cmu.edu>
Date: Mon, 15 Apr 2019 13:22:32 -0400
Subject: [PATCH] mavlink: set correct distance_sensor timestamp. Fixes #11840

When PX4FLOW is connected to PX4 through MAVLink (e.g., through a USB
port), the timestamp assigned to the distance_sensor was wrong. This fix
uses the same timestamp assigned to the optical_flow message created from
the same OPTICAL_FLOW_RAD MAVLink message.

Signed-off-by: Gabriel Moreno <gabrielm@cs.cmu.edu>
---
 src/modules/mavlink/mavlink_receiver.cpp | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 6c4f3b6cf9..7f98defe86 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -625,7 +625,7 @@ MavlinkReceiver::handle_message_optical_flow_rad(mavlink_message_t *msg)
 	struct distance_sensor_s d = {};
 
 	if (flow.distance > 0.0f) { // negative values signal invalid data
-		d.timestamp = _mavlink_timesync.sync_stamp(flow.integration_time_us * 1000); /* ms to us */
+		d.timestamp = f.timestamp;
 		d.min_distance = 0.3f;
 		d.max_distance = 5.0f;
 		d.current_distance = flow.distance; /* both are in m */
-- 
GitLab