PCL Overview

Data types

Point cloud data types in ROS

These are the current data structures in ROS that represent point clouds:

  • sensor_msgs::PointCloud

    • The first adopted point cloud message in ROS. Contains x, y and z points (all floats) as well as multiple channels; each channel has a string name and an array of float values. This served the initial point_cloud_mapping package in ROS (never released) and most of the visualization and data producers/consumers were based on this format prior to ROS 1.0.

  • sensor_msgs::PointCloud2

    • The newly revised ROS point cloud message (and currently the de facto standard in PCL), now representing arbitrary n-D (n dimensional) data. Point values can now be of any primitive data types (int, float, double, etc), and the message can be specified as 'dense', with height and width values, giving the data a 2D structure, e.g. to correspond to an image of the same region in space. For more information on the rationale behind the new structure, see: PCL_March_2010.pdf and pcl_icra2010.pdf

  • pcl::PointCloud<T>

    • The core point cloud class in the PCL library; can be templated on any of the Point types listed in point_types.h or a user-defined type. This class has a similar structure to the PointCloud2 message type, including a header. Converting between the message class and the point cloud template class is straightforward (see below), and most methods in the PCL library accept objects of both types. Still, it's better to work with this template class in your point cloud processing node, rather than with the message object, among other reasons because you can work with the individual points as objects rather than having to work with their raw data.

Determining the point type for a given point cloud message

Each point cloud object type gives you information about the field names in a different way.

If you have a sensor_msgs::PointCloud object, they're all floats. To find out their names, look at the elements of the channels() vector; each one has a name field.

If you have a sensor_msgs::PointCloud2 object, look at the elements of the fields() vector; each one has a name field and a datatype field. PCL has methods for extracting this information, see io.h.

If you have a pcl::PointCloud<T> object, you probably already know what type the fields are because you know what T is. If it's a topic published by another node that you didn't write, you'll have to look at the source for that node. PCL has methods for extracting this information, see io.h.

It has been suggested that it would be helpful if rostopic info could tell you what T is for a given PointCloud2 topic, but this hasn't been implemented yet.

Common PointCloud2 field names

Because field names are generic in the new PointCloud2 message, here's the list of commonly used names within PCL:

  • x - the X Cartesian coordinate of a point (float32)

  • y - the Y Cartesian coordinate of a point (float32)

  • z - the Z Cartesian coordinate of a point (float32)

  • rgb - the RGB (24-bit packed) color at a point (uint32)

  • rgba - the A-RGB (32-bit packed) color at a point (uint32), the field name is unfortunately misleading

  • normal_x - the first component of the normal direction vector at a point (float32)

  • normal_y - the second component of the normal direction vector at a point (float32)

  • normal_z - the third component of the normal direction vector at a point (float32)

  • curvature - the surface curvature change estimate at a point (float32)

  • j1 - the first moment invariant at a point (float32)

  • j2 - the second moment invariant at a point (float32)

  • j3 - the third moment invariant at a point (float32)

  • boundary_point - the boundary property of a point (e.g., set to 1 if the point is lying on a boundary) (bool)

  • principal_curvature_x - the first component of the direction of the principal curvature at a point (float32)

  • principal_curvature_y - the second component of the direction of the principal curvature at a point (float32)

  • principal_curvature_z - the third component of the direction of the principal curvature at a point (float32)

  • pc1 - the magnitude of the first component of the principal curvature at a point (float32)

  • pc2 - the magnitude of the second component of the principal curvature at a point (float32)

  • pfh - the Point Feature Histogram (PFH) feature signature at a point (float32[])

  • fpfh - the Fast Point Feature Histogram (FPFH) feature signature at a point (float32[])

  • ...

The complete list of field names and point types used in PCL can be found in pcl/point_types.hpp.

Point Cloud conversion

Converting between sensor_msgs::PointCloud2 and pcl::PointCloud<T> objects

Use pcl::fromROSMsg and pcl::toROSMsg from pcl_conversions. The versions of these methods provided by PCL (pcl::fromROSMsg and pcl::toROSMsg) are deprecated. The point_cloud::fromMsg() and point_cloud::toMsg() methods are deprecated and will be removed in an imminent release.

Converting between the `sensor_msgs::PointCloud` and `sensor_msgs::PointCloud2` format

The easiest way to convert between sensor_msgs/PointCloud and sensor_msgs/PointCloud2 messages is to run an instance of the point_cloud_converter node, which subscribes to topics of both types and publishes topics of both types.

If you want to do the conversion in your node, look at sensor_msgs::convertPointCloud2ToPointCloud and sensor_msgs::convertPointCloudToPointCloud2.

Publishing and subscribing to point cloud messages

Note: Use of the old PointCloud message type should be discontinued. Just for completeness, we'll summarize the subscription and publication operations for all three point cloud types below anyway.

Subscribing to different point cloud message types

For all of these, assume you've done the following:

   1 ros::NodeHandle nh;
   2 std::string topic = nh.resolveName("point_cloud");
   3 uint32_t queue_size = 1;

For sensor_msgs::PointCloud topics:

   1 // callback signature:
   2 void callback(const sensor_msgs::PointCloudConstPtr&);
   3 
   4 // create subscriber:
   5 ros::Subscriber sub = nh.subscribe(topic, queue_size, callback);

For sensor_msgs::PointCloud2 topics:

   1 // callback signature
   2 void callback(const sensor_msgs::PointCloud2ConstPtr&);
   3 
   4 // to create a subscriber, you can do this (as above):
   5 ros::Subscriber sub = nh.subscribe<sensor_msgs::PointCloud2> (topic, queue_size, callback);

For a subscriber that receives pcl::PointCloud<T> objects directly:

   1 // Need to include the pcl ros utilities
   2 #include <pcl_ros/point_cloud.h>
   3 
   4 // callback signature, assuming your points are pcl::PointXYZRGB type:
   5 void callback(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr&);
   6 
   7 // create a templated subscriber
   8 ros::Subscriber sub = nh.subscribe<pcl::PointCloud<pcl::PointXYZRGB> > (topic, queue_size, callback);

When subscribing to a pcl::PointCloud<T> topic with a sensor_msgs::PointCloud2 subscriber or viceversa, the conversion (deserialization) between the two types sensor_msgs::PointCloud2 and pcl::PointCloud<T> is done on the fly by the subscriber.

Publishing different point cloud types

As before, assume you've already done this:

   1 ros::NodeHandle nh;
   2 std::string topic = nh.resolveName("point_cloud");
   3 uint32_t queue_size = 1;

For sensor_msgs::PointCloud messages:

   1 // assume you get a point cloud message somewhere
   2 sensor_msgs::PointCloud cloud_msg;
   3 
   4 // advertise
   5 ros::Publisher pub = nh.advertise<sensor_msgs::PointCloud>(topic, queue_size);
   6 // and publish
   7 pub.publish(cloud_msg);

For sensor_msgs::PointCloud2 messages:

   1 // get your point cloud message from somewhere
   2 sensor_msgs::PointCloud2 cloud_msg;
   3 
   4 // to advertise you can do it like this (as above):
   5 ros::Publisher pub = nh.advertise<sensor_msgs::PointCloud2>(topic, queue_size);
   6 
   7 /// and publish the message
   8 pub.publish(cloud_msg);

If you have a pcl::PointCloud<T> object, you don't have to convert it to a message:

   1 // Need to include the pcl ros utilities
   2 #include "pcl_ros/point_cloud.h"
   3 
   4 // you have an object already, eg with pcl::PointXYZRGB points
   5 pcl::PointCloud<pcl::PointXYZRGB> cloud;
   6 
   7 // create a templated publisher
   8 ros::Publisher pub = nh.advertise<pcl::PointCloud<pcl::PointXYZRGB> > (topic, queue_size);
   9 
  10 // and just publish the object directly
  11 pub.publish(cloud);

The publisher takes care of the conversion (serialization) between sensor_msgs::PointCloud2 and pcl::PointCloud<T> where needed.

Wiki: pcl/Overview (last edited 2022-02-07 18:54:52 by IsaacSaito)