ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

answered 2015-01-22 15:45:02 -0500

joq gravatar image

The Velodyne driver estimates the time for each packet using the average of system time before and after reading it. Each packet contains its own time stamp.

That estimate is not very accurate, but it does work for all the supported devices. Models providing their own time stamps could theoretically do better, but would require a relatively complex Phase Locked Loop for converting device time into system time compatible with other ROS components.

The big error comes from converting VelodynePacket data to a PointCloud2, which has only a single time stamp for the entire cloud. While you can set npackets=1 so each packet is published as a separate point cloud preserving its estimated time, many users find it convenient to combine all the data for a complete rotation into a single cloud. Since the usual device speed is 600 RPM or 10Hz, the average time error for the points in a complete rotation is somewhere around half a rotation, or 50 msec.

The most obvious place where that causes problems is when transforming the point cloud into odometric coordinates while the device is moving. That is why transform.cc transforms each packet using its own time stamp and appends the result to the output cloud. While the time stamp of the output cloud has all the inaccuracies mentioned already, the positions of the points at least reflect the base_link->odom transform published by odometry at whatever accuracy and frequency those updates are provided.

In summary, if you need relatively accurate real time processing at the point cloud level, you should probably set npackets to some relatively small number.