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

Accessing layers in Velodyne Point cloud

asked 2014-02-24 19:40:20 -0500

sai gravatar image

updated 2014-02-25 00:48:54 -0500

Hi,

Is it possible to access layer by layer scans from velodyne HDL 32-E sensor. If no, Is there any other way round about way to get this functionality ?

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
4

answered 2014-02-25 05:56:45 -0500

joq gravatar image

updated 2014-02-28 05:22:43 -0500

By "layer" I suppose you mean the points associated with each of the 32 individual lasers.

The velodyne_pointcloud package reports the source of each point as a "ring number", using a sequential numbering of the lasers from 0 (lowest) to 31 (highest). For details, see my answer to this question.

EDIT: The velodyne_pointcloud package provides several nodes and nodelets for transforming raw data packets into a point cloud containing PointXYZRI with X, Y, Z, ring number, and intensity.

There is also a simple class which reads the point cloud and colors the points according to ring number, useful for visualization. Its message callback shows how to read the data and access the ring number of each point.

EDIT2: You can transform the point cloud for a single revolution into an organized 32xN cloud based on ring number, if you want. But, I don't see much advantage to doing that if the device is moving and the points are being transformed into the odom frame of reference.

edit flag offensive delete link more

Comments

Thats exactly what I am looking for, but i m not able to figure how to convert the sensor_msgs::PointCloud2 to pcl::PointXYZIR format.

sai gravatar image sai  ( 2014-02-25 17:56:18 -0500 )edit

Thanks for the edit, I was able to get access to each ring. I was thinking of creating a organized point cloud from velodyne. Accessing ring information will give the vertical relationship but how can i get the horizontal relation b/w the points in each ring ? Or can I have a buffer to accumulate rings and then just stack them ? Please correct me if I am wrong

sai gravatar image sai  ( 2014-02-27 14:50:23 -0500 )edit
1

Not sure what buffer you have in mind. You can use normal PCL operations to extract points from a cloud or combine multiple clouds. The 3D Euclidean distance between pairs of points is computed in the usual fashion.

joq gravatar image joq  ( 2014-02-28 05:27:40 -0500 )edit
1

Using a vector of pcl::PointCloud pointers should be a good way to accumulate the points of each ring.

mayuzumi gravatar image mayuzumi  ( 2017-02-02 21:32:45 -0500 )edit

Agreed, @mayuzumi, thanks!

joq gravatar image joq  ( 2017-02-04 10:18:30 -0500 )edit
0

answered 2018-04-13 00:59:06 -0500

Organizing velodyne point cloud and iterating over rings

pcl::PointCloud<pcl::pointxyz> rings[16];

sensor_msgs::PointCloud2ConstIterator<int> iter_ring(cloud_msg,"ring"); sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud_msg,"x"); sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud_msg,"y"); sensor_msgs::PointCloud2ConstIterator<float> iter_z(cloud_msg,"z");

for(;iter_x!=iter_x.end();++iter_x,++iter_ring,++iter_y,++iter_z) {
rings[iter_ring].push_back(pcl::PointXYZ(iter_x,iter_y,iter_y)); std::cout << "Ring Number = " << *iter_ring << std::endl; }

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2014-02-24 19:40:20 -0500

Seen: 6,948 times

Last updated: Apr 13 '18