PCL库学习笔记

zxl19 2021-11-28

我的点云库(Point Cloud Library,PCL)学习笔记。

PCL Hello World

模块

按照功能,PCL包含以下几个模块:

  1. 滤波(Filters);
  2. 特征(Features);
  3. 关键点(Keypoints);
  4. 配准(Registration);
  5. K-D树(KdTree);
  6. 八叉树(Octree);
  7. 分割(Segmentation);
  8. 采样一致(Sample Consensus);
  9. 表面(Surface);
  10. 深度图(Range Image);
  11. 输入输出(I/O);
  12. 可视化(Visualization);
  13. 公共(Common);
  14. 搜索(Search);

安装

sudo apt install libpcl-dev

CMakeLists

cmake_minimum_required(VERSION 2.6 FATAL_ERROR)
project(MY_GRAND_PROJECT)
find_package(PCL 1.3 REQUIRED COMPONENTS common io)
include_directories(${PCL_INCLUDE_DIRS})
link_directories(${PCL_LIBRARY_DIRS})
add_definitions(${PCL_DEFINITIONS})
add_executable(pcd_write_test pcd_write.cpp)
target_link_libraries(pcd_write_test ${PCL_LIBRARIES})

基础数据结构

  1. PCL在point_types.hpp中定义了支持的点的类型,以下为包含XYZ坐标的点的类型:

     // Define all point types that include XYZ data
     #define PCL_XYZ_POINT_TYPES   \
       (pcl::PointXYZ)             \
       (pcl::PointXYZI)            \
       (pcl::PointXYZL)            \
       (pcl::PointXYZRGBA)         \
       (pcl::PointXYZRGB)          \
       (pcl::PointXYZRGBL)         \
       (pcl::PointXYZLAB)          \
       (pcl::PointXYZHSV)          \
       (pcl::InterestPoint)        \
       (pcl::PointNormal)          \
       (pcl::PointXYZRGBNormal)    \
       (pcl::PointXYZINormal)      \
       (pcl::PointXYZLNormal)      \
       (pcl::PointWithRange)       \
       (pcl::PointWithViewpoint)   \
       (pcl::PointWithScale)       \
       (pcl::PointSurfel)          \
       (pcl::PointDEM)
    
  2. PCL对于点的类型进行了内存对齐,使用SSE(Streaming SIMD Extensions)指令集进行向量化运算加速,以pcl::PointXYZpcl::PointXYZIpcl::PointRGBA为例:

     // PointXYZ
     union {
       float data[4];
       struct {
         float x;
         float y;
         float z;
       };
     };
     // PointXYZI
     union {
       float data[4];
       struct {
         float x;
         float y;
         float z;
       };
     };
     union {
       struct {
         float intensity;
       };
       float data_c[4];
     };
     // PointXYZRGBA
     union {
       float data[4];
       struct {
         float x;
         float y;
         float z;
       };
     };
     union {
       union {
         struct {
           std::uint8_t b;
           std::uint8_t g;
           std::uint8_t r;
           std::uint8_t a;
         };
         float rgb;
       };
       std::uint32_t rgba;
     };
    
    • 点的坐标为float类型;
    • 可以通过结构体的数据成员直接读写对应的属性值;
    • 可以利用由于内存对齐多出来的data[3]保存信息,但是需要注意是float类型,防止截断;
  3. 点的定义和初始化:

     pcl::PointXYZ pt1;
     // 生成随机点
     pt1.x = 1024.0f * rand() / (RAND_MAX + 1.0f);
     pt1.y = 1024.0f * rand() / (RAND_MAX + 1.0f);
     pt1.z = 1024.0f * rand() / (RAND_MAX + 1.0f);
     pcl::PointXYZRGBA pt2;
     // 生成随机点
     pt2.x = 1024.0f * rand() / (RAND_MAX + 1.0f);
     pt2.y = 1024.0f * rand() / (RAND_MAX + 1.0f);
     pt2.z = 1024.0f * rand() / (RAND_MAX + 1.0f);
     // 设置颜色
     // 方法一:分别对于每个通道赋值,推荐使用
     pt2.r = 255;    // red: 0-255
     pt2.g = 0;      // green: 0-255
     pt2.b = 0;      // blue: 0-255
     pt2.a = 255;    // transparency: 0-255
     // 方法二:通过位运算转换为单精度浮点数,由于历史原因存在,不推荐使用
     std::uint8_t r = 255;
     std::uint8_t g = 0;
     std::uint8_t b = 0;
     std::uint32_t rgb = (r << 16) | (g << 8) | b;
     pt2.rgba = *(float *)(&rgb);  // makes the point red
    
  4. PCL中的点的类型可以与Eigen中的数据类型相互转换:

    • PCL使用typedef关键字重命名了Eigen::Map,通过内存映射进行相互转换:

        typedef Eigen::Map<Eigen::Array3f> Array3fMap;
        typedef const Eigen::Map<const Eigen::Array3f> Array3fMapConst;
        typedef Eigen::Map<Eigen::Array4f, Eigen::Aligned> Array4fMap;
        typedef const Eigen::Map<const Eigen::Array4f, Eigen::Aligned> Array4fMapConst;
        typedef Eigen::Map<Eigen::Vector3f> Vector3fMap;
        typedef const Eigen::Map<const Eigen::Vector3f> Vector3fMapConst;
        typedef Eigen::Map<Eigen::Vector4f, Eigen::Aligned> Vector4fMap;
        typedef const Eigen::Map<const Eigen::Vector4f, Eigen::Aligned> Vector4fMapConst;
      
    • PCL定义了返回引用和返回常引用两个版本的函数成员:

        #define PCL_ADD_EIGEN_MAPS_POINT4D                                                              \
          inline pcl::Vector3fMap getVector3fMap() { return (pcl::Vector3fMap(data)); }                 \
          inline pcl::Vector3fMapConst getVector3fMap() const { return (pcl::Vector3fMapConst(data)); } \
          inline pcl::Vector4fMap getVector4fMap() { return (pcl::Vector4fMap(data)); }                 \
          inline pcl::Vector4fMapConst getVector4fMap() const { return (pcl::Vector4fMapConst(data)); } \
          inline pcl::Array3fMap getArray3fMap() { return (pcl::Array3fMap(data)); }                    \
          inline pcl::Array3fMapConst getArray3fMap() const { return (pcl::Array3fMapConst(data)); }    \
          inline pcl::Array4fMap getArray4fMap() { return (pcl::Array4fMap(data)); }                    \
          inline pcl::Array4fMapConst getArray4fMap() const { return (pcl::Array4fMapConst(data)); }
      
    • 在调用时可以作为等号左值和等号右值使用:

        pcl::PointXYZ pt;
        Eigen::Vector3f vec;
        pt.getVector3fMap() = vec;
        vec = pt.getVector3fMap();
      
  5. PCL支持自定义点的类型:

    • 定义结构体,包括点的坐标和其他属性信息,注意需要声明内存对齐:

        struct EIGEN_ALIGN16 PointXYZIT {   // enforce SSE padding for correct memory alignment
          PCL_ADD_POINT4D                   // preferred way of adding a XYZ+padding
          uint8_t intensity;                // 反射强度
          float angle;                      // 线束俯仰角
          uint8_t ring;                     // 线束编号
          double timestamp;                 // 时间戳
          EIGEN_MAKE_ALIGNED_OPERATOR_NEW   // make sure our new allocators are aligned
        };
      
    • 使用POINT_CLOUD_REGISTER_POINT_STRUCT宏将自定义结构体注册到PCL命名空间中,可以直接使用自定义的点构建点云,注意必须在全局命名空间中注册:

        // clang-format off
        POINT_CLOUD_REGISTER_POINT_STRUCT(PointXYZIT,
                                          (float, x, x)
                                          (float, y, y)
                                          (float, z, z)
                                          (uint8_t, intensity, intensity)
                                          (float, angle, angle)
                                          (uint8_t, ring, ring)
                                          (double, timestamp, timestamp))
        // clang-format on
      

点云

  1. PCL在point_cloud.h中定义了模板类pcl::PointCloud,用于表示点云;
  2. pcl::PointCloud模板类的数据成员定义如下:

     pcl::PCLHeader header;                                          // 点云报头,包含seq(序号)、stamp(时间戳)、frame_id(坐标系ID)数据成员
     std::vector<PointT, Eigen::aligned_allocator<PointT>> points;   // 点云中的点
     std::uint32_t width;                                            // 点云宽度(如果点云按照图像形式组织,这里对应图像的列数,否则为点云中点的个数)
     std::uint32_t height;                                           // 点云高度(如果点云按照图像形式组织,这里对应图像的行数,否则为1)
     bool is_dense;                                                  // 点云中的点是否全部有效(即不存在Inf和NaN值)
     Eigen::Vector4f sensor_origin_;                                 // 传感器位置(可选)
     Eigen::Quaternionf sensor_orientation_;                         // 传感器朝向(可选)
    
  3. pcl::PointCloud模板类通过std::vector容器保存点云中的点,因此大部分函数成员都是对于std::vector容器中同名函数成员的直接封装,但是如果函数成员修改了points数据成员,则还需要同时维护widthheight数据成员,pcl::PointCloud模板类的部分函数成员定义如下:

    • 迭代器相关:

        typedef std::vector<PointT, Eigen::aligned_allocator<PointT>> VectorType;
        typedef typename VectorType::iterator iterator;
        typedef typename VectorType::const_iterator const_iterator;
        inline iterator begin() { return (points.begin()); }
        inline iterator end() { return (points.end()); }
        inline const_iterator begin() const { return (points.begin()); }
        inline const_iterator end() const { return (points.end()); }
      
    • 大小和容积相关:

        inline size_t size() const { return (points.size()); }
        inline void reserve(size_t n) { points.reserve(n); }
        inline bool empty() const { return points.empty(); }
      
        /** \brief Resize the cloud
         * \param[in] n the new cloud size
         */
        inline void resize(size_t n) {
          points.resize(n);
          if (width * height != n) {
            width = static_cast<uint32_t>(n);
            height = 1;
          }
        }
      
    • 元素访问:

        inline const PointT& operator[](size_t n) const { return (points[n]); }
        inline PointT& operator[](size_t n) { return (points[n]); }
        inline const PointT& at(size_t n) const { return (points.at(n)); }
        inline PointT& at(size_t n) { return (points.at(n)); }
        inline const PointT& front() const { return (points.front()); }
        inline PointT& front() { return (points.front()); }
        inline const PointT& back() const { return (points.back()); }
        inline PointT& back() { return (points.back()); }
      
    • 元素增加和删除:

        /** \brief Insert a new point in the cloud, at the end of the container.
         * \note This breaks the organized structure of the cloud by setting the height to 1!
         * \param[in] pt the point to insert
         */
        inline void push_back(const PointT& pt) {
          points.push_back(pt);
          width = static_cast<uint32_t>(points.size());
          height = 1;
        }
      
        /** \brief Removes all points in a cloud and sets the width and height to 0. */
        inline void clear() {
          points.clear();
          width = 0;
          height = 0;
        }
      
        // 除此之外还定义了insert()、erase()、swap()等函数成员
        // 由于使用较少并且重载形式较多,本文不再赘述
      
  4. 点云的定义:

     pcl::PointCloud<pcl::PointXYZ> cloud;
     std::vector<pcl::PointXYZ> data = cloud.points;
    
    • 为了方便计算,可以使用std::vector<Eigen::Vector3f>来保存点云中点的坐标;
    • Eigen::Vector3f不是固定大小可向量化的Eigen对象,因此不需要考虑内存对齐问题;
  5. 点云的初始化:

     pcl::PointCloud<pcl::PointXYZ> cloud1;
     pcl::PointCloud<pcl::PointXYZ> cloud2;
     x1 = cloud1.points[i].x;
     y1 = cloud1.points[i].y;
     z1 = cloud1.points[i].z;
     // 以下两种方法均可以向点云中添加点,但是均会将有组织点云转换为无组织点云
     // 方法一:通过模板类的函数成员添加点,自动维护width和height数据成员
     cloud2.push_back(cloud1.points[i]);
     // 方法二:通过points数据成员的函数成员添加点
     cloud2.points.push_back(cloud1.points[i]);
     cloud2.points.emplace_back(cloud1.points[i]);   // C++11引入,执行效率高
     // 注意在添加完成后需要手动维护width和height数据成员
     cloud2.resize(cloud2.points.size());
    
  6. 点云与点云指针之间的赋值:

     pcl::PointCloud<pcl::PointXYZ> cloud1;
     pcl::PointCloud<pcl::PointXYZ> cloud2;
     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ptr1(new pcl::PointCloud<pcl::PointXYZ>);
     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ptr2(new pcl::PointCloud<pcl::PointXYZ>);
     // 浅拷贝,指向同一块内存地址
     cloud1 = cloud2;
     cloud_ptr1 = cloud_ptr2;
     *cloud_ptr1 = *cloud_ptr2;
     // 深拷贝,指向不同的内存地址
     cloud1 = *cloud_ptr1;
     *cloud_ptr1 = cloud1;
     pcl::copyPointCloud(cloud1, cloud2);  // 深拷贝点云,重载形式较多,本文不再赘述
     cloud_ptr1 = cloud1.makeShared();     // 返回指向深拷贝对象的智能指针
    
    • 推荐使用copyPointCloud()函数深拷贝点云,定义如下:

        template <typename PointInT, typename PointOutT>
        void pcl::copyPointCloud(const pcl::PointCloud<PointInT>& cloud_in, pcl::PointCloud<PointOutT>& cloud_out) {
          // Allocate enough space and copy the basics
          cloud_out.header = cloud_in.header;
          cloud_out.width = cloud_in.width;
          cloud_out.height = cloud_in.height;
          cloud_out.is_dense = cloud_in.is_dense;
          cloud_out.sensor_orientation_ = cloud_in.sensor_orientation_;
          cloud_out.sensor_origin_ = cloud_in.sensor_origin_;
          cloud_out.points.resize(cloud_in.points.size());
      
          if (cloud_in.points.size() == 0) return;
      
          if (isSamePointType<PointInT, PointOutT>())
            // Copy the whole memory block
            memcpy(&cloud_out.points[0], &cloud_in.points[0], cloud_in.points.size() * sizeof(PointInT));
          else
            // Iterate over each point
            for (size_t i = 0; i < cloud_in.points.size(); ++i) copyPoint(cloud_in.points[i], cloud_out.points[i]);
        }
      
    • 推荐使用makeShared()函数成员创建指向深拷贝对象的智能指针,定义如下:

        typedef boost::shared_ptr<PointCloud<PointT>> Ptr;
        typedef boost::shared_ptr<const PointCloud<PointT>> ConstPtr;
      
        /** \brief Copy the cloud to the heap and return a smart pointer
         * Note that deep copy is performed, so avoid using this function on non-empty clouds.
         * The changes of the returned cloud are not mirrored back to this one.
         * \return shared pointer to the copy of the cloud
         */
        inline Ptr makeShared() const { return Ptr(new PointCloud<PointT>(*this)); }
      
  7. 点云拼接:

     pcl::PointCloud<pcl::PointXYZ> cloud_a, cloud_b, cloud_c;
     pcl::PointCloud<pcl::Normal> n_cloud_b;
     pcl::PointCloud<pcl::PointNormal> p_n_cloud_c;
     // concatenate points
     cloud_c  = cloud_a;
     cloud_c += cloud_b;
     // concatenate fields
     pcl::concatenateFields(cloud_a, n_cloud_b, p_n_cloud_c);
    
  8. 关于有组织点云(organized point cloud):

    • 有组织点云指的是按照图像(或矩阵)形式组织的点云,通常来源于双目相机和飞行时间(Time of Flight,ToF)相机;
      • 有组织点云示例:

          cloud1.width = 640;       // Image-like organized structure, with 480 rows and 640 columns,
          cloud1.height = 480;      // thus 640*480=307200 points total in the dataset
        
      • 无组织点云示例:

          cloud2.width = 307200;
          cloud2.height = 1;        // unorganized point cloud dataset with 307200 points
        
    • 有组织点云的优点是可以通过相邻行列信息提高最近邻操作的效率,进而提高PCL中部分算法的计算速度;
    • 可以使用isOrganized()函数成员判断点云是否有组织:

        cloud1.isOrganized();       // false
        cloud2.isOrganized();       // true
      
    • isOrganized()函数成员定义如下:

        /** \brief Return whether a dataset is organized (e.g., arranged in a structured grid).
        * \note The height value must be different than 1 for a dataset to be organized.
        */
        inline bool isOrganized() const { return (height > 1); }
      

滤波

VoxelGrid

#include <pcl/filters/voxel_grid.h>

pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);

// Create the filtering object
pcl::VoxelGrid<pcl::PCLPointCloud2> sor;
sor.setInputCloud(cloud);
sor.setLeafSize(0.01f, 0.01f, 0.01f);
sor.filter(*cloud_filtered);

ApproximateVoxelGrid

#include <pcl/filters/approximate_voxel_grid.h>

pcl::PointCloud<pcl::PointXYZ>::Ptr input_cloud(new pcl::PointCloud<pcl::PointXYZ>);
pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_cloud(new pcl::PointCloud<pcl::PointXYZ>);

// Filtering input scan to roughly 10% of original size to increase speed of registration.
pcl::ApproximateVoxelGrid<pcl::PointXYZ> approximate_voxel_filter;
approximate_voxel_filter.setLeafSize(0.2, 0.2, 0.2);
approximate_voxel_filter.setInputCloud(input_cloud);
approximate_voxel_filter.filter(*filtered_cloud);

StatisticalOutlierRemoval

#include <pcl/filters/statistical_outlier_removal.h>

pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);

// Create the filtering object
pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor;
sor.setInputCloud(cloud);
sor.setMeanK(50);
sor.setStddevMulThresh(1.0);
sor.filter(*cloud_filtered);

RadiusOutlierRemoval

#include <pcl/filters/radius_outlier_removal.h>

pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);

pcl::RadiusOutlierRemoval<pcl::PointXYZ> outrem;
// build the filter
outrem.setInputCloud(cloud);
outrem.setRadiusSearch(0.8);
outrem.setMinNeighborsInRadius(2);
outrem.setKeepOrganized(true);
// apply filter
outrem.filter(*cloud_filtered);

ConditionalRemoval

#include <pcl/filters/conditional_removal.h>

pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);

pcl::ConditionAnd<pcl::PointXYZ>::Ptr range_cond(new pcl::ConditionAnd<pcl::PointXYZ>());
range_cond->addComparison(pcl::FieldComparison<pcl::PointXYZ>::ConstPtr(new pcl::FieldComparison<pcl::PointXYZ>("z", pcl::ComparisonOps::GT, 0.0)));
range_cond->addComparison(pcl::FieldComparison<pcl::PointXYZ>::ConstPtr(new pcl::FieldComparison<pcl::PointXYZ>("z", pcl::ComparisonOps::LT, 0.8)));
// build the filter
pcl::ConditionalRemoval<pcl::PointXYZ> condrem;
condrem.setCondition(range_cond);
condrem.setInputCloud(cloud);
condrem.setKeepOrganized(true);
// apply filter
condrem.filter(*cloud_filtered);

配准

ICP

#include <pcl/registration/icp.h>

pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in(new pcl::PointCloud<pcl::PointXYZ>);
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_out(new pcl::PointCloud<pcl::PointXYZ>);

pcl::IterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ> icp;
icp.setInputSource(cloud_in);
icp.setInputTarget(cloud_out);

pcl::PointCloud<pcl::PointXYZ> Final;
icp.align(Final)
std::cout << "has converged:" << icp.hasConverged() << " score: " <<
icp.getFitnessScore() << std::endl;
std::cout << icp.getFinalTransformation() << std::endl;

NDT

#include <pcl/registration/ndt.h>

pcl::PointCloud<pcl::PointXYZ>::Ptr target_cloud(new pcl::PointCloud<pcl::PointXYZ>);
pcl::PointCloud<pcl::PointXYZ>::Ptr input_cloud(new pcl::PointCloud<pcl::PointXYZ>);
pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_cloud(new pcl::PointCloud<pcl::PointXYZ>);

// Initializing Normal Distributions Transform (NDT).
pcl::NormalDistributionsTransform<pcl::PointXYZ, pcl::PointXYZ> ndt;

// Setting scale dependent NDT parameters
// Setting minimum transformation difference for termination condition.
ndt.setTransformationEpsilon(0.01);
// Setting maximum step size for More-Thuente line search.
ndt.setStepSize(0.1);
// Setting Resolution of NDT grid structure (VoxelGridCovariance).
ndt.setResolution(1.0);

// Setting max number of registration iterations.
ndt.setMaximumIterations(35);

// Setting point cloud to be aligned.
ndt.setInputSource(filtered_cloud);
// Setting point cloud to be aligned to.
ndt.setInputTarget(target_cloud);

// Set initial alignment estimate found using robot odometry.
Eigen::AngleAxisf init_rotation(0.6931, Eigen::Vector3f::UnitZ());
Eigen::Translation3f init_translation(1.79387, 0.720047, 0);
Eigen::Matrix4f init_guess = (init_translation * init_rotation).matrix();

// Calculating required rigid transform to align the input cloud to the target cloud.
pcl::PointCloud<pcl::PointXYZ>::Ptr output_cloud(new pcl::PointCloud<pcl::PointXYZ>);
ndt.align(*output_cloud, init_guess);

std::cout << "Normal Distributions Transform has converged:" << ndt.hasConverged()
          << " score: " << ndt.getFitnessScore() << std::endl;

// Transforming unfiltered, input cloud using found transform.
pcl::transformPointCloud(*input_cloud, *output_cloud, ndt.getFinalTransformation());

KdTree

#include <pcl/kdtree/kdtree_flann.h>

pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;
pcl::PointXYZ searchPoint;

kdtree.setInputCloud(cloud);

// K nearest neighbor search
int K = 10;
std::vector<int> pointIdxKNNSearch(K);
std::vector<float> pointKNNSquaredDistance(K);

// 返回值为找到最近邻的个数
kdtree.nearestKSearch(searchPoint, K, pointIdxKNNSearch,
                      pointKNNSquaredDistance);
// 最近邻点
// (*cloud)[pointIdxKNNSearch[i]]

// Neighbors within radius search
std::vector<int> pointIdxRadiusSearch;
std::vector<float> pointRadiusSquaredDistance;
float radius;

// 返回值为找到最近邻的个数
kdtree.radiusSearch(searchPoint, radius, pointIdxRadiusSearch,
                    pointRadiusSquaredDistance);
// 最近邻点
// (*cloud)[pointIdxRadiusSearch[i]]

输入输出

PCD文件格式

  1. 文件头需要严格按照以下顺序:

     VERSION
     FIELDS
     SIZE
     TYPE
     COUNT
     WIDTH
     HEIGHT
     VIEWPOINT
     POINTS
     DATA
    
    • VERSION:PCD文件版本,PCL要求0.7;
    • FIELDS:点的每个维度对应的数据含义:

        FIELDS x y z                                # XYZ data
        FIELDS x y z rgb                            # XYZ + colors
        FIELDS x y z normal_x normal_y normal_z     # XYZ + surface normals
        FIELDS j1 j2 j3                             # moment invariants
      
    • SIZE:点的每个维度占据的字节数:

      数据类型 字节数
      unsigned char / char 1
      unsigned short / short 2
      unsigned int / int / float 4
      double 8
    • TYPE:点的每个维度对应的数据类型:

      数据类型 字符表示
      有符号:int8(char)、int16(short)、int32(int) I
      无符号:uint8(unsigned char)、uint16(unsigned short)、uint32(unsigned int) U
      float F
    • COUNT:点的每个维度包含的元素个数,默认为1;
    • WIDTH:点云的列数,对于无组织点云为点的总数;
    • HEIGHT:点云的行数,对于无组织点云为1;
    • VIEWPOINT:点云的采集视角,使用向量表示平移,使用四元数表示旋转,默认旋转和平移为0:

        tx ty tz qw qx qy qz
      
    • POINTS:点的总数;
    • DATA:存储方式:

      存储方式 说明 优势
      ascii 使用ASCII码存储 简洁直观,便于第三方软件读取
      binary 使用二进制存储,内存拷贝 读取速度最快
      binary_compressed 使用二进制存储,LZF算法压缩 压缩后大小为binary的30%-60%,读取时需要解压缩
  2. 数据每个点占一行,使用nan表示NaN:

     p_1
     p_2
     p_3
     p_4
     ...
    
     p_n
    
  3. 文件头示例:

     # .PCD v.7 - Point Cloud Data file format
     VERSION .7
     FIELDS x y z rgb
     SIZE 4 4 4 4
     TYPE F F F F
     COUNT 1 1 1 1
     WIDTH 213
     HEIGHT 1
     VIEWPOINT 0 0 0 1 0 0 0
     POINTS 213
     DATA ascii
     0.93773 0.33763 0 4.2108e+06
     0.90805 0.35641 0 4.2108e+06
     0.81915 0.32 0 4.2108e+06
     0.97192 0.278 0 4.2108e+06
     0.944 0.29474 0 4.2108e+06
    

输入

#include <pcl/io/pcd_io.h>

pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
pcl::io::loadPCDFile<pcl::PointXYZ>("test_pcd.pcd", *cloud);
std::cout << "Loaded " << cloud->width * cloud->height
          << " data points from test_pcd.pcd with the following fields: "
          << std::endl;

输出

#include <pcl/io/pcd_io.h>

pcl::PointCloud<pcl::PointXYZ> cloud;
pcl::io::savePCDFileASCII("test_pcd.pcd", cloud);
std::cerr << "Saved " << cloud.size () << " data points to test_pcd.pcd." << std::endl;

可视化

pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud;
//... populate cloud
pcl::visualization::CloudViewer viewer("Simple Cloud Viewer");
viewer.showCloud(cloud);
while(!viewer.wasStopped()) {
}
  1. 在可视化界面中使用+-来增大和减小显示点的大小;
  2. 在可视化界面中使用Alt++Alt+-来放大和缩小画面;
  3. 在可视化界面中使用1-5设置点云颜色:

    • 1:单色;
    • 2:按照x坐标着色;
    • 3:按照y坐标着色;
    • 4:按照z坐标着色;
    • 5:按照反射强度着色;
  4. 在可视化界面中使用g显示或隐藏坐标轴;
  5. 在可视化界面中使用u显示或隐藏颜色图;
  6. 在可视化界面中使用o打开或关闭正交投影;
  7. 在可视化界面中使用f拉近到光标所在位置;
  8. 在可视化界面中使用r重置相机视角;
  9. 在可视化界面中使用j截图;
  10. 在可视化界面中使用e退出;

资料

网站

  1. Point Cloud Library
  2. pcl
  3. pcl-docs
  4. PCL(Point Cloud Library)学习指南&资料推荐(2023版)-双愚的文章-知乎
  5. PCL(Point Cloud Library)学习入门指南&代码实践(最新版)
  6. pcl常用小知识

GitHub

  1. HuangCongQing/pcl-learning
  2. MNewBie/PCL-Notes
  3. methylDragon/pcl-ros-tutorial
  4. LarryDong/csdn_codes

参考

  1. pcl::PointXYZRGBA-Stack Overflow
  2. PCL新增自定义点类型-飞我执笔的文章-知乎
  3. Using STL Containers with Eigen
  4. 点云与点云指针之间的赋值1-CSDN博客
  5. 点云与点云指针之间的赋值2-CSDN博客
  6. 点云与点云指针之间的赋值3-CSDN博客
  7. 关于PCL库中makeshared转换智能指针的问题-小透明的文章-知乎
  8. pcl_viewer-CSDN博客