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 2013-04-02 14:38:19 -0500

joq gravatar image

Are you using the ROS velodyne stack to provide the data?

If so, the velodyne_pointcloud package handles converting the raw data packets received from the device into ROS sensor_msgs/PointCloud2 messages. The HDL-32E spews out about 700,000 points per second in a highly permuted order, the HDL-64E provides about 1,000,000 points per second in a very different and less regular order. So, velodyne_pointcloud keeps things simpler by always producing "unordered" point clouds as the data arrive from the device.

To prevent that unordered representation from losing useful information, velodyne_pointcloud publishes its data using a custom PCL point definition: velodyne_pointcloud::PointXYZIR, defined in the velodyne_pointcloud/point_types.h header. A PointXYZIR differs from the standard PCL PointXYZI (X, Y, Z, and intensity) in adding an additional field containing the "laser ring number" from which the point was measured.

Each ring number corresponds to a device-specific laser number, with the numbers are reordered so that ring 0 corresponds to the innermost laser (at the lowest angle) and ring 31 corresponds to the outermost laser (at the highest angle) of a 32E (that would be ring 63 on a 64E). That encoding ensures that adjacent lasers are labelled with adjacent ring numbers, which is not at all true of the hardware laser numbers. The actual mapping is defined in the velodyne_driver/ring_sequence.h header, provided by the velodyne_driver package. The permutation for a 32E is the same as the first 32 of the 64E.

So, it should be possible to produce an ordered point cloud from the unordered PointXYZIR data by using the ring numbers as rows in a 2D representation. I have not heard of anyone actually doing that, and I suspect that the results might be somewhat confused when the device is in motion.

Are you using the ROS velodyne stack to provide the data?

If so, the velodyne_pointcloud package handles converting the raw data packets received from the device into ROS sensor_msgs/PointCloud2 messages. The HDL-32E spews out about 700,000 points per second in a highly permuted order, the HDL-64E provides about 1,000,000 points per second in a very different and less regular order. So, velodyne_pointcloud keeps things simpler by always producing "unordered" point clouds as the data arrive from the device.

To prevent that unordered representation from losing useful information, velodyne_pointcloud publishes its data using a custom PCL point definition: velodyne_pointcloud::PointXYZIR, defined in the velodyne_pointcloud/point_types.h header. A PointXYZIR differs from the standard PCL PointXYZI (X, Y, Z, and intensity) in adding an additional field containing the "laser ring number" from which the point was measured.

Each ring number corresponds to a device-specific laser number, with the numbers are reordered so that ring 0 corresponds to the innermost laser (at the lowest angle) and ring 31 corresponds to the outermost laser (at the highest angle) of a 32E (that would be ring 63 on a 64E). That encoding ensures that adjacent lasers are labelled with adjacent ring numbers, which is not at all true of the hardware laser numbers. The actual mapping is defined in the velodyne_driver/ring_sequence.h header, provided by the velodyne_driver package. The permutation for a 32E is the same as the first 32 lasers of the 64E.64E, so the same conversions work for both.

So, it should theoretically be possible to produce an ordered point cloud from the unordered PointXYZIR data by using the ring numbers as rows in a 2D representation. I have not heard of anyone actually doing that, and I suspect that the results might be become somewhat confused when the device is in motion.

Are you using the ROS velodyne stack to provide the data?

If so, the velodyne_pointcloud package handles converting the raw data packets received from the device into ROS sensor_msgs/PointCloud2 messages. The HDL-32E spews out about 700,000 points per second in a highly permuted order, the HDL-64E provides about 1,000,000 points per second in a very different and less regular order. So, velodyne_pointcloud keeps things simpler by always producing "unordered" point clouds as the data arrive from the device.

To prevent that unordered representation from losing useful information, velodyne_pointcloud publishes its data using a custom PCL point definition: velodyne_pointcloud::PointXYZIR, defined in the velodyne_pointcloud/point_types.h header. A PointXYZIR differs from the standard PCL PointXYZI (X, Y, Z, and intensity) in adding an additional field containing the "laser ring number" from which the point was measured.

Each ring number corresponds to a device-specific laser number, with but the numbers are reordered so that ring 0 corresponds to the innermost laser (at the lowest angle) and ring 31 corresponds to the outermost laser (at the highest angle) of a 32E (that would be ring 63 on a 64E). That encoding ensures that adjacent lasers are labelled with adjacent ring numbers, which is not at all true of the hardware laser numbers. The actual mapping is defined in the velodyne_driver/ring_sequence.h header, provided by the velodyne_driver package. The permutation for a 32E is the same as the first 32 lasers of the 64E, so the same conversions work for both.

So, it should theoretically be possible to produce an ordered point cloud from the unordered PointXYZIR data by using the ring numbers as rows in a 2D representation. I have not heard of anyone actually doing that, and I suspect that the results might become somewhat confused when the device is in motion.

click to hide/show revision 4
move header links to github sources

Are you using the ROS velodyne stack to provide the data?

If so, the velodyne_pointcloud package handles converting the raw data packets received from the device into ROS sensor_msgs/PointCloud2 messages. The HDL-32E spews out about 700,000 points per second in a highly permuted order, the HDL-64E provides about 1,000,000 points per second in a very different and less regular order. So, velodyne_pointcloud keeps things simpler by always producing "unordered" point clouds as the data arrive from the device.

To prevent that unordered representation from losing useful information, velodyne_pointcloud publishes its data using a custom PCL point definition: velodyne_pointcloud::PointXYZIR, defined in the velodyne_pointcloud/point_types.h header. A PointXYZIR differs from the standard PCL PointXYZI (X, Y, Z, and intensity) in adding an additional field containing the "laser ring number" from which the point was measured.

Each ring number corresponds to a device-specific laser number, but the numbers are reordered so that ring 0 corresponds to the innermost laser (at the lowest angle) and ring 31 corresponds to the outermost laser (at the highest angle) of a 32E (that would be ring 63 on a 64E). That encoding ensures that adjacent lasers are labelled with adjacent ring numbers, which is not at all true of the hardware laser numbers. The actual mapping is defined in the velodyne_driver/ring_sequence.h header, provided by the velodyne_driver package. The permutation for a 32E is the same as the first 32 lasers of the 64E, so the same conversions work for both.

So, it should theoretically be possible to produce an ordered point cloud from the unordered PointXYZIR data by using the ring numbers as rows in a 2D representation. I have not heard of anyone actually doing that, and I suspect that the results might become somewhat confused when the device is in motion.