33 #ifndef TIMEREFERENCEPUBLISHER_H
34 #define TIMEREFERENCEPUBLISHER_H
37 #include <sensor_msgs/TimeReference.h>
45 int pub_queue_size = 5;
47 pub = node.
advertise<sensor_msgs::TimeReference>(
"imu/time_ref", pub_queue_size);
52 if (packet.containsSampleTimeFine())
54 const uint32_t SAMPLE_TIME_FINE_HZ = 10000UL;
55 const uint32_t ONE_GHZ = 1000000000UL;
57 sensor_msgs::TimeReference
msg;
59 t_fine = packet.sampleTimeFine();
60 sec = t_fine / SAMPLE_TIME_FINE_HZ;
61 nsec = (t_fine % SAMPLE_TIME_FINE_HZ) * (ONE_GHZ / SAMPLE_TIME_FINE_HZ);
63 if (packet.containsSampleTimeCoarse())
65 sec = packet.sampleTimeCoarse();
70 msg.header.stamp = timestamp;
72 msg.time_ref = sample_time;