Jianghc's Blog

Back

写在前面的#

最近在读LIO-SAM代码中发现了一些有关于PCL库和ROS之间数据格式转换的相关问题,因此特地在网上找了些资料总结了下,希望后面看起来较为方便。。。。

常用message消息类型#

PCL对ROS的接口提供PCL数据结构的转换,通过通过ROS提供的以消息为基础的转换系统系统。这有一系列的转换函数提供用来转换原始的PCL数据类型成消息型。一些最有用常用的的message类型列举在下面。
std_msgs:Header 这不是真的消息类型,但是用在Ros消息里面的每一个部分。它包含了消息被发送的时间和序列号和框名。在PCL库中等于pcl::Header类型 sensor_msgs::PointCloud2 这是最重要的类型。这个消息通常是用来转换pcl::PointCloud类型的,pcl::PCLPointCloud2这个类型也很重要,因为前面版本的可能被废除。 pcl_msgs::PointIndices 该类型存储属于点云里面的点的下标,在pcl里面等于pcl::PointIndices pcl_msgs::PolygonMesh 该类型包括消息需要描述多边形网眼,就是顶点和边,在pcl里面等于pcl::PolygonMesh pcl_msgs::Vertices 该类型包含了一系列的顶点作为一个数组的下标,来描述一个多边形。在pcl里面等于pcl::Vertices pcl_msgs::ModelCoefficients 这存储了一个模型的不同的系数,比如描述一个平面需要4个系数。在PCL里面等于pcl::ModelCoefficients

PCL库中提供的相应转换函数#

使用前需要加入头文件

#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>

#include <pcl_conversions/pcl_conversions.h>
#include <pcl/ros/conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
plaintext

下面是在pcl_conversions命名空间里面提供的函数

return valuefunction
voidcopyImageMetaData (const sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
voidcopyPCLImageMetaData (const pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
voidcopyPCLPointCloud2MetaData (const pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
voidcopyPointCloud2MetaData (const sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2)
voidfromPCL (const pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
voidfromPCL (const std::vector< pcl::PCLPointField > &pcl_pfs, std::vector< sensor_msgs::PointField > &pfs)
voidfromPCL (const pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
voidmoveFromPCL (pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
voidmoveFromPCL (pcl::PCLPointCloud2 &pcl_pc2, sensor_msgs::PointCloud2 &pc2)
voidmoveToPCL (sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
voidmoveToPCL (sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2)
voidmoveToPCL (pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
voidtoPCL (const sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
voidtoPCL (const sensor_msgs::PointCloud2 &pc2, pcl::PCLPointCloud2 &pcl_pc2)

PCL对ROS接口的相关总结#

  1. void toROSMsg(const pcl::PointCloud &, sensor_msgs::PointCloud2 &) 实现的功能是将pcl里面的pcl::PointCloudpcl::PointXYZ cloud 转换成ros里面的sensor_msgs::PointCloud2 output这个类型。
  2. void fromROSMsg(const sensor_msgs::PointCloud2 &, pcl::PointCloud&) 转为PCL中的pcl::PointCloud类型
  3. void moveFromROSMsg(sensor_msgs::PointCloud2 &, pcl::PointCloud &) 这里和上面的只差了一个const 转换为pcl::PointCloud 类型

需要注意的问题 通过查询相关资料ROS里面是否加move,主要用于区分浅拷贝和深拷贝的问题,正常版本执行的是一个深拷贝(完全拷贝),而move版的是浅拷贝,并使源数据作废。 浅拷贝和深拷贝 浅拷贝只是对指针的拷贝(&),拷贝后两个指针指向同一个内存空间,深拷贝不但对指针进行拷贝(const &),而且对指针指向的内容进行拷贝,经深拷贝后的指针是指向两个不同地址的指针。

PCL点云库的一些使用#

初始化点云对象指针

pcl::PointCloud<T>::Ptr pointCloudKeyPose(new pcl::PointCloud<T>());
plaintext

其中T为pcl对应的点云类型,常见的pcl点云类型有:

PointXYZ   成员变量:float x,y,z;
访问方式1:
float x = cloud.points[i].x;  
访问方式2:
float x = cloud.points[i].data[0];
---------------------------------------------------------------------------
PointXYZI    
成员变量: float x, y, z, intensity;
---------------------------------------------------------------------------
PointXYZRGBA     
成员变量: float x, y, z; uint32_t rgba;  (rgba信息被包含在一个整型变量中)
---------------------------------------------------------------------------
PointXYZRGB     
成员变量: float x, y, z, rgb;
---------------------------------------------------------------------------
PointXY    
成员变量: float x, y;
---------------------------------------------------------------------------
Normal    
成员变量: float normal_x,normal_y,normal_z, curvature;
---------------------------------------------------------------------------
PointNormal    
成员变量: float x, y, z,normal_x,normal_y,normal_z, curvature
---------------------------------------------------------------------------
PointXYZRGBNormal    
成员变量: float x, y, z, rgb, normal_x,normal_y,normal_z, curvature;
---------------------------------------------------------------------------
PointXYZINormal
成员变量: float x, y, z, intensity, normal_x,normal_y,normal_z, curvature;
plaintext

PCL常见点云类型

使用点云的KDtree功能 由于这个本身不像FLANN库是个通用的最近邻库,这里的最近邻实际上只包含点云类型的最近邻,LIO-SAM的作者实际上在这里取巧了,将位置信息作为点信息存储,从而完成了最近邻keyframe的查找,实现submap的构建, 常规代码如下:

// 声明
pcl::PointCloud<PointType>::Ptr cloudKeyPoses3D;
pcl::KdTreeFLANN<PointType>::Ptr kdtreeSurroundingKeyPoses;

// 按照最近邻半径获取的id信息和对应的平方距离
std::vector<int> pointSearchInd;
std::vector<float> pointSearchSqDis;

// 构建kdtree
kdtreeSurroundingKeyPoses->setInputCloud(cloudKeyPoses3D);
// 完成kdtree的相关搜索  第一个变量是一个T类型的点云中的点
kdtreeSurroundingKeyPoses->radiusSearch(cloudKeyPoses3D->back(), (double)surroundingKeyframeSearchRadius, pointSearchInd, pointSearchSqDis);
plaintext

使用点云VoxelGrid降采样功能 VoxelGrid滤波器是使用体素化网格的方法实现下采样,并保持点云的形状特征。通过在点云数据中创建三维体素栅格,然后用每个体素的重心来近似表达体素中的其它点。这种方法比用体素中心来逼近的方法更慢,但它对采样点对应曲面的表示更为准确。常规操作代码如下:

#include<pcl/filters/voxel_grid.h>

// 创建降采样滤波器对象
pcl::VoxelGrid<PointType> downSizeFilterSurroundingKeyPoses;
// 单位m,三维空间栅格的大小
downSizeFilterSurroundingKeyPoses.setLeafSize(surroundingKeyframeDensity, surroundingKeyframeDensity, surroundingKeyframeDensity);
// 点云输入
downSizeFilterSurroundingKeyPoses.setInputCloud(surroundingKeyPoses);
// 降采样执行
downSizeFilterSurroundingKeyPoses.filter(*surroundingKeyPosesDS);
plaintext
如何在ROS中使用PCL----数据格式相关
https://525511.xyz/blog/%E5%A6%82%E4%BD%95%E5%9C%A8ros%E4%B8%AD%E4%BD%BF%E7%94%A8pcl-%E6%95%B0%E6%8D%AE%E6%A0%BC%E5%BC%8F%E7%9B%B8%E5%85%B3
Author Haochen Jiang
Published at August 16, 2021
Comment seems to stuck. Try to refresh?✨