[ros-users] point cloud questions

Radu Bogdan Rusu rusu at willowgarage.com
Thu Jul 29 23:26:59 UTC 2010


Hi Michael,

On 07/29/2010 02:20 PM, Michael Styer wrote:
> Hello the list,
>
> I'm doing some work with PCL, and I'm finding myself a little bit
> confused by the various point cloud messages and classes floating
> around.

Ah no problem. Let's see if we can clear that up :)

> So far I think I understand the following, but correct me if any of
> these are wrong:
> * the old point cloud message type was sensor_msgs::PointCloud;

correct.

> * this has been superseded by sensor_msgs::PointCloud2;

correct. If the reasons are not clear why we had to come up with a new structure, please see these presentations:

http://www.ros.org/wiki/pcl?action=AttachFile&do=get&target=PCL_March_2010.pdf
http://rbrusu.com/wp-content/uploads/2010/05/pcl_icra2010.pdf

> * the PCL library works with objects of type pcl::PointCloud<T>, where T
> is one of the defined pcl:: types or a user-defined type;

yes, PCL works with pcl::PointCloud<T> but also with sensor_msgs::PointCloud2 (see the filters). The reason is twofold:
1) we want our users to be comfortable while coding algorithms. They need to be able to access data in an easy fashion 
such as cloud.points[i].x for the X coordinate.
2) we do need general purpose sensor_msgs::PointCloud2 operations sometimes, and the filtering module is a good example, 
where we need to provide the SAME data type at output as it was at input, except some points need to be 
added/removed/modified/etc.

> * a pcl::PointCloud object can be obtained from a PointCloud2 message
> using the point_cloud::fromMsg() function;

this got changed in 0.2.x (small rename), but yes, the principle is the same. sensor_msgs::PointCloud2 -> 
pcl::fromROSMsg () -> pcl::PointCloud<T>

> * although point_cloud::Publisher::publish() accepts (and appears to
> publish) pcl::PointCloud<T>  objects directly, it converts them to
> sensor_msgs::PointCloud2 messages in order to publish them (I was
> confused about this for a while).

correct. We do have a more generic structure publisher on our to-do lists, one that would allow us to publish 
pcl::PointCloud<T> directly, but that is not implemented yet. In the meantime, we do the conversion step.

> But I also have a number of questions that I haven't been able to figure
> out, so if anyone can help me out here I'd be very grateful!

That's why we're here! ;)

> 1) The PCL demo stack publishes point clouds as
> sensor_msgs::PointCloud2, but also sets up a point_cloud_converter node
> to convert to sensor_msgs::PointCloud. Why does it do this? Is there a
> reason I should prefer publishing PointCloud messages over PointCloud2
> messages, or vice versa?

Ah. That is no longer the case in 0.2.x. The reason why we _had_ that in, was because most of our tools were built to 
consume sensor_msgs::PointCloud messages, and we couldn't change things overnight. Even if we could, we still like to 
guarantee a certain backwards compatibility. Hence, the point_cloud_converter package which does the to/from conversion 
between sensor_msgs::PointCloud and sensor_msgs::PointCloud2. Since our visualization and other data consumers packages 
have caught up since, we no longer need the converter step, as we can operate directly on sensor_msgs::PointCloud2 data 
types.

> 2) What's the function of the height and width fields in the
> pcl::PointCloud<T>  class? In particular, in my node I want to create an
> output point cloud which is a subset of the points in the input point
> cloud; given the subset, what should the height and width of the output
> point cloud be? Do the height and width of the input point cloud refer
> to the geometric area enclosing the points, or to the size of the point
> cloud vector/matrix?


Good question. We should document this a little bit better (though it is documented in the format message itself). The 
new sensor_msgs::PointCloud2 can represent organized datasets, while the older format (sensor_msgs::PointCloud) 
couldn't. This means that now we can represent stereo 3D point cloud data, (or TOF, or even laser, etc), by specifying a 
width and a height which corresponds to an image. What does this mean?

- Say you have an RGB image organized as width x height, given by some sensor (i.e., stereo camera)
- Say you have a point cloud acquired using the same stereo camera, organized as width x height
- Now you have a perfect 1-1 correspondence between the RGB texture at each pixel and each point in the cloud! Hooray!

(between you and me, we're working on a 2D to 3D feature estimation architecture as we speak - one that would allow you 
to estimate any 2D feature and attach it to a 3D point in a PointCloud2).

> 3) For a given node that publishes a sensor_msgs::PointCloud2 topic, is
> there any way for another node to determine the type of the enclosed
> points? Or is that information only visible in the source?

It is. That's the reason why we have "fields" inside the PointCloud2 topic. take a look at sensor_msgs::PointField.

> That's all I have at the minute... :) Thanks for any advice you can
> provide.

Sure, you're welcome!

Cheers,
Radu.
-- 
| Radu Bogdan Rusu | http://rbrusu.com/



More information about the ros-users mailing list