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

Bytes in Velodyne Message

asked 2015-10-19 14:40:51 -0500

Morris gravatar image

I am using matlab_rosbag to read in the Velodyne points from a ROS bag. I see that there are 32 uint8 bytes for each LIDAR return. Some of them are documented as follows: 1 - 4: X, 5 - 8: Y, 9 - 12: Z, 17 - 20: Intensity, 21 - 22: Ring.

But what are the remaining bytes used for? (13 - 16, and 23 - 32). If there are more useful data in those bytes I would like to make use of them.

Also I don't know how to interpret Ring -- what is that?

Thank you very much!

DM

edit retag flag offensive close merge delete

Comments

1

Not an answer, but would it perhaps be an idea to run the bag file through a quick conversion session with velodyne_pointcloud doing the conversion for you, storing the pointclouds in a new bag and reading that in matlab?

gvdhoorn gravatar image gvdhoorn  ( 2015-10-20 03:44:56 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
4

answered 2015-10-20 16:04:14 -0500

joq gravatar image

updated 2015-10-20 16:07:10 -0500

I think you are asking about the /velodyne_points output from velodyne_pointcloud, is that right?

Those data are published as a PCL point cloud, which is required to be 16-byte aligned. The driver defines a custom PointXYZIR point type in order to add an extra field containing the ring number. The layout is defined in velodyne_pointcloud/point_types.h, with a four-byte float for each of the three coordinates and the intensity, followed by two bytes for the ring number. Unfortunately, the remaining 14 bytes in each entry are just padding, required by PCL to ensure alignment consistent with the use of vector floating point instructions.

The ring sequence is defined in velodyne_driver/ring_sequence.h. It is a way of representing which laser produced each point in the cloud. Since the actual device laser numbers are somewhat scrambled, the driver re-orders them into a range from zero to N-1, where N is the number of physical lasers. Ring zero is the lower-most laser, ring one is next. Ring N-1 is the upper-most.

While the PointCloud2 representation is convenient to work with in PCL, it is not at all byte-efficient. For later playback and analysis, I recommend saving the raw /velodyne_packets topic, then using velodyne_pointcloud, on the saved messages.

If you don't care about the ring number, you can convert the custom PointXYZIR to a standard PCL PointXYZI, which fits neatly into 16 bytes.

Hope that helps. Let me know if I answered the wrong question...

edit flag offensive delete link more

Comments

Ah, that explains the puzzling output in /velodyne_points. I'll try saving /velodyne_packets instead. Thanks very much!

Morris gravatar image Morris  ( 2015-10-21 01:10:48 -0500 )edit
0

answered 2015-10-20 03:40:40 -0500

gvdhoorn gravatar image

@joq will have a more direct answer, but in the meantime:

The packet formats for the various lasers are documented in the documentation provided by Velodyne on their site. For the HDL-64E fi (page 9) and the HDL-32E (page 19).

Alternatively, the velodyne_pointcloud package implements the deserialisation in src/lib/rawdata.cc (here for the everything not a VLP16 fi).

edit flag offensive delete link more

Comments

Thanks. Now that @joq answered I realize that my question was really about /velodyne_pointcloud.

Morris gravatar image Morris  ( 2015-10-21 01:11:55 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-10-19 14:40:51 -0500

Seen: 1,622 times

Last updated: Oct 20 '15