forked from Archive/PX4-Autopilot
mavlink_receiver: set timestamp to gps_inject_data_topic
This commit is contained in:
parent
c95192d050
commit
fcadc69e52
|
@ -2742,6 +2742,7 @@ MavlinkReceiver::handle_message_gps_rtcm_data(mavlink_message_t *msg)
|
||||||
memcpy(gps_inject_data_topic.data, gps_rtcm_data_msg.data,
|
memcpy(gps_inject_data_topic.data, gps_rtcm_data_msg.data,
|
||||||
math::min((int)sizeof(gps_inject_data_topic.data), (int)sizeof(uint8_t) * gps_inject_data_topic.len));
|
math::min((int)sizeof(gps_inject_data_topic.data), (int)sizeof(uint8_t) * gps_inject_data_topic.len));
|
||||||
|
|
||||||
|
gps_inject_data_topic.timestamp = hrt_absolute_time();
|
||||||
_gps_inject_data_pub.publish(gps_inject_data_topic);
|
_gps_inject_data_pub.publish(gps_inject_data_topic);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue