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

Velodyne UDP packets, ROS messages, and PCD files: Where does the time go?

asked 2015-01-14 13:12:32 -0500

brianthelion gravatar image

updated 2015-01-14 13:48:51 -0500

Here is what I understand about the tool chain that turns Velodyne UDP packets into PCD files:

  1. (input.cc) ROS sits in a poll() loop and collects Velodyne UDP packets from the network. It wraps each packet payload in a VelodynePacket object and sets the time stamp on the new object to the time the payload was received.
  2. (driver.cc) Many VelodynePacket objects are buffered before sending them on as a VelodyneScan object. The new object gets the time stamp of the last VelodynePacket that it holds.
  3. (convert.cc, transform.cc) Various subscribers receive the VelodyneScan objects and re-publish them as PointCloud2 objects, one per scan. They all do pretty much the same thing: Iterate over the scan -- oldest to newest -- while calling RawData::unpack() on every VelodynePacket. The final PointCloud2 objects contain points ordered from oldest to newest -- minus some filtering; see next -- and are guaranteed not to contain any partial UDP payloads. Their time stamps are copied from their respective VelodyneScan objects.
  4. (rawdata.cc) The unpack() method is where the UDP payloads actually get parsed. The payloads contain each laser return in terms of distance, and unpack() turns distance into (x, y, z) location. Not all the points in each payload are reported as some violate angle and range constraints.
  5. (bag_to_pcd.cc) This executable pulls PointCloud2 messages off a ROS bag and turns them into PCD files. No substantive processing is involved; it's all I/O. Each PCD file represents a single PointCloud2 message, with its time stamp given in the PCD file name.

Questions

  • Have I misunderstood anything in here?
  • How meaningful are the PCD file names -- eg, the VelodyneScan time stamps -- in a realtime sense?
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2015-01-14 13:14:58 -0500

brianthelion gravatar image

updated 2015-01-15 14:25:09 -0500

OP's Analysis

In our system, the PCD file names are all about 0.1s apart. Given a published packet rate of 1808 packets/s for our Velodyne device (32E), this means that each PCD file should span roughly 180 packets. The temporal error that we're interested in is the per-point error within a given PCD file, e[i, j] = T-t[i, j], where T is the time stamp reported in the PCD file name and t[i, j] is the actual time that point i, j was recorded by the device. Here, i means packet i out of 180 and j means point j out of 384 in the packet. (384 points = 12 firings * each of 32 lasers.)

If my understanding of the tool chain is right, e[i, j] is a function of primarily of (1) the construction of each packet in the Velodyne device, (2) transmission latency, (3) buffering in the kernel and ROS code, (4) and re-stamping of the VelodyneScan object with the received time of the last packet in its buffer. It seems to me that max(e[i, j]) is basically the interval between between one PCD time stamp and the next, plus transmission and buffering latency.

We can't model network latency and buffering too well, so I'll give a lower bound: In my case, max(e[i, j]) is at least 0.1s.

edit flag offensive delete link more
0

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.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2015-01-14 13:12:32 -0500

Seen: 2,663 times

Last updated: Jan 22 '15