point_cloud_perception: ann | cminpack | flann | pcl | pcl_ros | pcl_tf | pcl_tutorials | pcl_visualization | point_cloud_converter | terminal_tools | vtk
Package Summary
PCL - Point Cloud Library: a comprehensive library for n-D Point Clouds and 3D geometry processing. The library contains numerous state-of-the art algorithms for: filtering, feature estimation, surface reconstruction, registration, model fitting and segmentation, etc.
- Author: Maintained by Radu Bogdan Rusu. See AUTHORS for the complete list of authors.
- License: BSD
- Repository: ros-pkg (https://code.ros.org/svn/ros-pkg)
Contents
New in ROS C-Turtle
The latest version of PCL is: 0.1.9 (2010-06-29). Check the stack ChangeList for a list of changes.
PCL graphics by Marius Sucan.
PCL Overview
PCL is meant to incorporate a multitude of 3D processing algorithms that operate on point cloud data, including: filtering, feature estimation, surface reconstruction, model fitting, segmentation, registration, etc.
To simplify development, PCL is split into a series of smaller code libraries:
- libpcl_features: implements many 3D features such as surface normals and curvatures, boundary point estimation, moment invariants, principal curvatures, Point Feature Histograms (PFH), Fast Point Feature Histograms (FPFH), etc
- libpcl_filters: implements data filters such as downsampling, outlier removal, indices extraction, projections, etc
- libpcl_io: implements I/O operations such as writing to/reading from PCD (Point Cloud Data) files, and BAG files
- libpcl_segmentation: implements cluster extraction, model fitting via sample consensus methods for a variety of parametric models (planes, cylinders, spheres, lines, etc), polygonal prism extraction, etc
- libpcl_surface: implements surface reconstruction techniques, meshing, convex hulls, Moving Least Squares, etc
- libpcl_registration: implements point cloud registration methods such as ICP, etc
PCL is a modern templated library, that uses Boost for a lot of internal operations. Most of PCL can be accessed and used via headers.
The code is written in an SSE friendly format to take advantage of modern CPU optimizations. Several algorithmic implementations for OpenMP and TBB (Threading Building Blocks) also exist.
The following represent a set of slides describing PCL 0.1 as of mid-March 2010. PCL_March_2010.pdf. Please note that the slides do not represent the latest changes in PCL, as the library is undergoing massive development.
PCL Features List
PCL (0.1.x) currently contains over 100 classes. Some of the most important ones are illustrated below:
3D Features: BoundaryEstimation, NormalEstimation{OMP,TBB}, PFHEstimation, PrincipalCurvaturesEstimation, MomentInvariantsEstimation, FPFHEstimation{OMP}
Filters: ExtractIndices, PassThrough, ProjectInliers, RadiusOutlierRemoval, StatisticalOutlierRemoval, VoxelGrid
- I/O: PCDReader, PCDWriter, BAGReader
Segmentation: SACSegmentation, SACSegmentationFromNormals, EuclideanClusterExtraction, ExtractPolygonalPrismData
Surface reconstruction: ConvexHull2D, MovingLeastSquares
Registration: IterativeClosestPoint, IterativeClosestPointNonLinear
The segmentation framework allows model fitting for a variety of primitive shapes (planes, cylinders, sphere, lines, etc). Most of the library is backed by different types of spatial locators (e.g., kd-trees). Check the tutorials section for more information.
PCL 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 RGB-A (32-bit packed) color at a point (uint32)
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.
PCL Segmentation constants
PCL uses the following constants for all Sample Consensus segmentation algorithms:
* const static int SACMODEL_PLANE = 0; * const static int SACMODEL_LINE = 1; * const static int SACMODEL_CIRCLE2D = 2; * const static int SACMODEL_CIRCLE3D = 3; * const static int SACMODEL_SPHERE = 4; * const static int SACMODEL_CYLINDER = 5; * const static int SACMODEL_CONE = 6; * const static int SACMODEL_TORUS = 7; * const static int SACMODEL_ORIENTED_LINE = 8; * const static int SACMODEL_ORIENTED_PLANE = 9; * const static int SACMODEL_PARALLEL_LINES = 10; * const static int SACMODEL_NORMAL_PLANE = 11;
(the complete list is given in include/pcl/sample_consensus/model_types.h)
Alternatively, you can choose between any of the following Sample Consensus algorithms:
* const static int SAC_RANSAC = 0; * const static int SAC_LMEDS = 1; * const static int SAC_MSAC = 2; * const static int SAC_RRANSAC = 3; * const static int SAC_RMSAC = 4; * const static int SAC_MLESAC = 5;
(the complete list is given in include/pcl/sample_consensus/method_types.h)
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 }






