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

point_cloud2.read_points and then?

asked 2016-07-27 07:28:35 -0500

Mehdi. gravatar image

I have a topic publishing a point cloud of type sensors_msgs.PointCloud2. I can subscribe to it and read it using sensors_msgs.point_cloud2.read_points function but then I get and object of type "generator". How do I access the coordinates of the points in this object? I want to write a service that checks the maximum allowed height in some specific target areas (the point cloud represents the ceiling). I am using python.

edit retag flag offensive close merge delete

3 Answers

Sort by ยป oldest newest most voted
3

answered 2016-07-27 09:59:22 -0500

NEngelhard gravatar image

read_points gives you a generator (keyword 'yield'). So you can just iterate over it to find your obstacles and not crash your shiny robot

from sensor_msgs.msg import PointCloud2
from sensor_msgs import point_cloud2

def callback_pointcloud(data):
    assert isinstance(data, PointCloud2)
    gen = point_cloud2.read_points(data)
    print type(gen)
    for p in gen:
      print p  # type depends on your data type, first three entries are probably x,y,z
edit flag offensive delete link more

Comments

What would be the other 3 entries ? are they RGB color values ?

Avhi gravatar image Avhi  ( 2021-12-19 21:22:26 -0500 )edit

When I use this code, it gives me an assertion error: cloud is not a sensor_msgs.msg.PointCloud2. What would be causing this and how would I fix it?

bwhal gravatar image bwhal  ( 2023-05-15 11:47:14 -0500 )edit
2

answered 2016-07-27 09:58:26 -0500

Mehdi. gravatar image

updated 2016-07-27 10:00:47 -0500

After looking into the source code I found out that this read_points is a generator function that yields the next value of a cloud each time it is called. It works also as an iterator and calling it in a loop will deliver all pointcloud points:

cloud_points = []
for p in point_cloud2.read_points(pc2, field_names = ("x", "y", "z"), skip_nans=True):
    cloud_points.append(p)

Here pc2 is my pointcloud of type sensor_msgs/PointCloud2

and cloud_points will then be a list of 3D points forming the cloud.

edit flag offensive delete link more

Comments

2

This would be too slow. Try this instead:

cloud_points = list(point_cloud2.read_points(cloud, skip_nans=True, field_names = ("x", "y", "z")))
ozgurovic gravatar image ozgurovic  ( 2017-11-14 08:23:14 -0500 )edit
1

answered 2022-09-13 07:32:27 -0500

Lbern gravatar image

updated 2022-09-15 04:02:35 -0500

As of ROS2 humble there is also read_points_numpy (see here) which would give you directly a 2D NumPy array. For example:

cloud = point_cloud2.read_points_numpy(
    msg, field_names=['x', 'y', 'z', "intensity"], skip_nans=True)

Note that there also exists a read_points_list (see here) at least for galactic, foxy, and humble which would have simplified the code of the other answers.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2016-07-27 07:28:35 -0500

Seen: 11,998 times

Last updated: Sep 15 '22