[Documentation] [TitleIndex] [WordIndex

Documentation

Filters

ROS interface

PCL natively supports and works with the new sensor_msgs/PointCloud2 message. The old format sensor_msgs/PointCloud is not supported in PCL.

Registering a user-defined point type

User defined point structures can be registered using PCL macros. If the structure is flat (only scalar data members) and all field names are standard, a user can use the concise form POINT_CLOUD_REGISTER_FLAT_POINT_STRUCT. If the structure contains other struct or array members, or has any non-standard named fields, the more general POINT_CLOUD_REGISTER_POINT_STRUCT should be used. For example:

   1 #include <stdint.h>
   2 #include "pcl/ros/register_point_struct.h"
   3 
   4 namespace my_ns
   5 {
   6   struct MyPoint
   7  {
   8    float x;
   9    float y;
  10    float z;
  11     uint32_t w;
  12   };
  13 } // namespace my_ns
  14 
  15 // Must be used in the global namespace with the fully-qualified name
  16 // of the point type.
  17 POINT_CLOUD_REGISTER_FLAT_POINT_STRUCT(
  18   my_ns::MyPoint,
  19   (float, x)
  20   (float, y)
  21   (float, z)
  22   (uint32_t, w));
  23 
  24 
  25 namespace my_ns2
  26 {
  27   struct Position
  28   {
  29     float x;
  30     float y;
  31     float z;
  32   }
  33   struct MyComplexPoint
  34   {
  35     Position pos;
  36     uint32_t w;
  37     float normal[3];
  38   };
  39 
  40 } // namespace my_ns2
  41 
  42 POINT_CLOUD_REGISTER_POINT_STRUCT(
  43   my_ns2::MyComplexPoint,
  44   (float,    pos.x,     x)
  45   (float,    pos.y,     y)
  46   (float,    pos.z,     z)
  47   (uint32_t, w,         w)
  48   (float,    normal[0], normal_x)
  49   (float,    normal[1], normal_y)
  50   (float,    normal[2], normal_z));

The registration list contains (datatype, accessor, tag) 3-tuples. In the flat case, the accessor and tag are the same.

The registration macro, incidentally, also registers the point struct with Boost.Fusion as an associative type, meaning you can access fields by tag:

   1 #include <boost/fusion/sequence/intrinsic/at_key.hpp>
   2 
   3 my_ns::MyPoint pt1 = {1.0, 2.5, 6.1, 42};
   4 MyComplexPoint pt2 = {{1.0, 2.5, 6.1}, 42, {0.0, 1.0, 0.0}};
   5 
   6 printf("pt1 has x = %f\n", pt1.x);
   7 printf("pt2 has x = %f\n", pt2.pos.x);
   8 // is identical to...
   9 printf("pt1 has x = %f\n", boost::fusion::at_key<point_cloud::fields::x>(pt1));
  10 printf("pt2 has x = %f\n", boost::fusion::at_key<point_cloud::fields::x>(pt2));

This opens the possibility of writing generic point cloud algorithms that operate efficiently on arbitrary user-defined point types.

Publishing point clouds

There is a specialized point_cloud::Publisher for point clouds (doc). It's templated on a registered point type. The publish() methods take point clouds as a container of points (plus dimensions for structured clouds), where the container is anything recognized by Boost.Range. That includes STL containers, fixed-size arrays, pairs of pointers or iterators, etc.

Usage example:

   1 #include "my_point.h"
   2 #include "pcl/ros/publisher.h"
   3 #include <ros/ros.h>
   4 
   5 int main(int argc, char** argv)
   6 {
   7   std::vector<my_ns::MyPoint> pt_cloud;
   8   my_ns::MyPoint pt = {1.0, 2.5, 6.1, 42};
   9   pt_cloud.push_back (pt);
  10 
  11   ros::init (argc, argv, "point_cloud_publisher");
  12   ros::NodeHandle nh;
  13   point_cloud::Publisher<my_ns::MyPoint> pub;
  14   pub.advertise (nh, "cloud", 1);
  15 
  16   ros::Rate loop_rate (4);
  17   while (nh.ok ())
  18   {
  19     pub.publish (pt_cloud); // unordered, may be invalid points
  20     ros::spinOnce ();
  21     loop_rate.sleep ();
  22   }
  23 }

Subscribing to point clouds

There is a specialized point_cloud::Subscriber for point clouds (doc). It's templated on a registered point type. The subscriber callback takes a const-ptr to pcl::PointCloud (doc) which is also templated on the point type.

Usage example:

   1 #include "my_point.h"
   2 #include "pcl/ros/subscriber.h"
   3 
   4 void
   5   callback (const pcl::PointCloud<my_ns::MyPoint>::ConstPtr& msg)
   6 {
   7   printf ("Cloud: width = %u, height = %u\n", msg->width, msg->height);
   8   BOOST_FOREACH (const my_ns::MyPoint& pt, msg->points)
   9     printf("\t(%f, %f, %f, %u)\n", pt.x, pt.y, pt.z, pt.w);
  10 }
  11 
  12 int
  13   main (int argc, char** argv)
  14 {
  15   ros::init (argc, argv, "point_cloud_listener");
  16   ros::NodeHandle nh;
  17   point_cloud::Subscriber<my_ns::MyPoint> sub;
  18   sub.subscribe (nh, "cloud", 1, callback);
  19   ros::spin ();
  20 }

2024-04-20 12:52