33 #ifndef VELODYNE_DRIVER_TIME_CONVERSION_HPP 34 #define VELODYNE_DRIVER_TIME_CONVERSION_HPP 50 const int HALFHOUR_TO_SEC = 1800;
52 if (nominal_stamp.
sec > stamp.
sec) {
53 if (nominal_stamp.
sec - stamp.
sec > HALFHOUR_TO_SEC) {
54 retval.
sec = retval.
sec + 2*HALFHOUR_TO_SEC;
56 }
else if (stamp.
sec - nominal_stamp.
sec > HALFHOUR_TO_SEC) {
57 retval.
sec = retval.
sec - 2*HALFHOUR_TO_SEC;
63 const int HOUR_TO_SEC = 3600;
66 uint32_t usecs = (uint32_t) ( ((uint32_t) data[3]) << 24 |
67 ((uint32_t) data[2] ) << 16 |
68 ((uint32_t) data[1] ) << 8 |
69 ((uint32_t) data[0] ));
71 uint32_t cur_hour = time_nom.
sec / HOUR_TO_SEC;
73 (usecs % 1000000) * 1000);
78 #endif //VELODYNE_DRIVER_TIME_CONVERSION_HPP
ros::Time resolveHourAmbiguity(const ros::Time &stamp, const ros::Time &nominal_stamp)
Function used to check that hour assigned to timestamp in conversion is correct. Velodyne only return...
ros::Time rosTimeFromGpsTimestamp(const uint8_t *const data)