mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-22 09:28:58 +00:00
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>
This commit is contained in:
committed by
Lorenz Meier
parent
93d52581ef
commit
f9324fb76a
@@ -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 */
|
||||
|
||||
Reference in New Issue
Block a user