Functions
time_conversion.hpp File Reference
#include <pcap.h>
#include <ros/ros.h>
#include <ros/time.h>
Include dependency graph for time_conversion.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Functions

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 returns time since the top of the hour, so if the computer clock and the velodyne clock (gps-synchronized) are a little off, there is a chance the wrong hour may be associated with the timestamp. More...
 
ros::Time rosTimeFromGpsTimestamp (const uint8_t *const data, const struct pcap_pkthdr *header=NULL)
 

Function Documentation

◆ resolveHourAmbiguity()

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 returns time since the top of the hour, so if the computer clock and the velodyne clock (gps-synchronized) are a little off, there is a chance the wrong hour may be associated with the timestamp.

Parameters
stamptimestamp recovered from velodyne
nominal_stamptime coming from computer's clock
Returns
timestamp from velodyne, possibly shifted by 1 hour if the function arguments disagree by more than a half-hour.

Definition at line 51 of file time_conversion.hpp.

◆ rosTimeFromGpsTimestamp()

ros::Time rosTimeFromGpsTimestamp ( const uint8_t *const  data,
const struct pcap_pkthdr *  header = NULL 
)

Definition at line 64 of file time_conversion.hpp.



velodyne_driver
Author(s): Jack O'Quin, Patrick Beeson, Michael Quinlan, Yaxin Liu
autogenerated on Fri Aug 2 2024 08:46:21