PCL函数库摘要——3D点云特征描述与提取

1.Class pcl::Feature< PointInT, PointOutT >

类Feature是所有特征相关模块中其他类的基类,定义了所有描述子常用的函数接口。

#include <pcl/features/feature.h>
Feature () 
//  空构造函数
virtual  ~Feature () 
//  空析构函数
void  setSearchSurface (const PointCloudInConstPtr &cloud) 
//  设置搜索时近邻的来源点云,参数cloud指向搜索时被搜索的点云对象,常常用稠密的原始点云,而不用稀疏的下采样后的点云,在特征描述和提取中查询点往往是关键点。
PointCloudInConstPtr  getSearchSurface () const 
//  获得搜索时近邻的来源点云指针。  
void  setSearchMethod (const KdTreePtr &tree) 
// 设置搜索时所用的搜索机制,参数tree指向搜索时所用的搜索对象,例如 kd-tree, octree等对象。
KdTreePtr  getSearchMethod () const 
//  获取设置搜索时所用的搜索机制
double  getSearchParameter () const 
//  获得搜索时的内参
void  setKSearch (int k) 
//  设置搜索时所用的k近邻个数,参数k为设置搜索近邻个数。
int  getKSearch () const 
//  设置搜索时所用的k近邻个数,
void  setRadiusSearch (double radius) 
//  设置搜索时所用的球半径,参数radius为设置搜索球体半径。
double  getRadiusSearch () const 
//  获得搜索时所用的球半径。
void  compute (PointCloudOut &output) 
//  计算特征描述子重载函数,在子类中实现不同的具体计算,参数output存储计算之后得到的特征描述子点云对象。
virtual void  setInputCloud (const PointCloudConstPtr &cloud) 
//  设置输入点云,参数cloud指向输入点云对象。
virtual void  setIndices (const IndicesPtr &indices) 
//  与setInputCloud配合使用, indices为指向点云索引向量的指针引用,如果设置了此函数则算法的输入点云为indices中索引向量指定的点云集合,否则为setInput-Cloud设置的整个输入点云。
virtual void  setIndices (const IndicesConstPtr &indices) 
//  同上,只是要求indices不能被函数改变。
virtual void  setIndices (const PointIndicesConstPtr &indices) 
//  同上,但indices是 PointIndices 的结构体链表,可以看做是点云索引向量指针的链表理解。
virtual void  setIndices (size_t row_start, size_t col_start, size_t nb_rows, size_t nb_cols) 
//  与setInputCloud 配合使用,此函数只限于有序点云,如果设置了此函数,则算法的输入点云为第row_start行,第 col_start列开始, nb_rows行和 nb_cols列限定的矩形区域所覆盖的点云,否则为setInputCloud设置的整个输入点云。                                    

2.Class pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >

类ShapeContext3DEstimation实现了3D形状内容描述子(3D shape context descriptor)算法,详细可参考文献(Recognizing Objects in Range Data Using Regional Point Descriptors) ,其可以用于三维模型的识别、检索等领域。

#include <pcl/features/3dsc.h>
ShapeContext3DEstimation (bool random=false) 
//  构造函数
virtual  ~ShapeContext3DEstimation () 
//  析构函数
size_t  getAzimuthBins () 
//  获得沿方向角划分的数目。
size_t  getElevationBins () 
//  获得沿俯仰角划分的数目。
size_t  getRadiusBins () 
//  获得沿径向划分的数目。
void  setMinimalRadius (double radius) 
//  设置最小径向半径。
double  getMinimalRadius () 
//  获得最小径向半径。
void  setPointDensityRadius (double radius) 
//  设置点密度半径,该半径用于计算局部点密度密度=该半径内的点数。
double  getPointDensityRadius () 
//  获得点密度半径。
void  setInputNormals (const PointCloudNConstPtr &normals) 
//  设置输入点云对应的法线数据对象。
void  compute (PointCloudOut &output) 
//  计算输出,output的类型默认为pcl:: ShapeContext,其有两个成员,一为rffloat[9],存储以当前计算点为圆心的局部坐标系,另一为desc std::vector<float>存储计算得到的特征向量

3.Class pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >

类BOARDLocalReferenceFrameEstimation实现文献(On the repeatability of the local reference frame for partial shape matching)中讲的局部坐标系估计方法,该方法在估计局部坐标系时对处理点云边缘或有孔洞处有特殊的处理方式,比以往常用的局部坐标系估计方法稳定,可重复性好。

#include <pcl/features/board.h>
BOARDLocalReferenceFrameEstimation () 
//  构造函数
virtual  ~BOARDLocalReferenceFrameEstimation () 
//  空析构函数
void  setTangentRadius (float radius) 
//  设置估计x,y坐标轴时所用的最远点距离。
float  getTangentRadius () const 
//  获得估计x,y坐标轴时所用的最远点距离。
void  setFindHoles (bool find_holes) 
//  设置在估计局部坐标系时是否考虑孔洞的因素。
bool  getFindHoles () const 
//  获得在估计局部坐标系时是否考虑孔洞的因素。
void  setMarginThresh (float margin_thresh) 
//  设置在搜索半径的百分比超过该搜索半径比例的搜索区域点作为边界支撑域处理。
float  getMarginThresh () const 
//  获得搜索边缘阈值。
void  setCheckMarginArraySize (int size) 
//  设置在边界支撑域搜索孔洞时,对边界支撑域的细分数。
int  getCheckMarginArraySize () const 
//  获得在边界支撑域搜索孔洞时,对边界支撑域的细分数。
void  setHoleSizeProbThresh (float prob_thresh) 
//  假设在搜索的支撑域上有一个孔洞,设置该孔洞在局部xy平面上支撑圆周对应弧形区域所占的角度比例最小值,即所占比例小于该值则认为不是孔洞或缺失区域。
float  getHoleSizeProbThresh () const 
//  获得该孔洞在局部xy平面上支撑圆周对应弧形区域所占的角度比例最小值
void  setSteepThresh (float steep_thresh) 
//  假设探测到一孔洞,设置孔洞边缘的法线与孔洞平面的法线的偏离阈值,来判断是否有法线偏离严重的点。
float  getSteepThresh () const 
  Gets the minimum steepness that the normals of the points situated on the borders of the hole, with reference to the normal of the best point found by the algorithm, must have in order to be considered in the calculation of the Reference Frame. More... 
void  compute (PointCloudOut &output) 
//  计算输出output存储局部坐标系数据结构,其点类型为ReferenceFrame。

4.Class pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >

类BoundaryEstimation实现估计一组点集是否处于指定点的投影区域的边缘位置。

#include <pcl/features/boundary.h>
BoundaryEstimation () 
//  空构造函数
bool  isBoundaryPoint (const pcl::PointCloud< PointInT > &cloud, int q_idx, const std::vector< int > &indices, const Eigen::Vector4f &u, const Eigen::Vector4f &v, const float angle_threshold) 
//  判断某点是否在给定点集投影到平面上的投影区域的边缘,参数cloud指向输入点云,q_idx需要判断是否在边沿上的点索引,indices需要投影到平面上点集合的索引,u、v确定投影平面,利用void getCoordinateSystemOnPlane ( const PointNT&p_coeff, Eigen::Vector4f &u, Eigen:: Vector4f &v)获取, angle_threshold 为判断时需要的阈值角度。
bool  isBoundaryPoint (const pcl::PointCloud< PointInT > &cloud, const PointInT &q_point, const std::vector< int > &indices, const Eigen::Vector4f &u, const Eigen::Vector4f &v, const float angle_threshold) 
//  判断某点是否在给定点集投影到平面上的投影区域的边缘,参数cloud指向输入点云,q_point需要判断是否在边沿上的点指针,indices需要投影到平面上点集合的索引,u、v确定投影平面,利用void getCoordinateSystemOnPlane ( const PointNT&p_coeff, Eigen::Vector4f &u, Eigen:: Vector4f &v)获取, angle_threshold 为判断时需要的阈值角度。
void  setAngleThreshold (float angle) 
//  设置将点标记为边界或规则的决定边界(角度阈值)。
float  getAngleThreshold () 
//  获得将点标记为边界或规则的决定边界(角度阈值)。
void  getCoordinateSystemOnPlane (const PointNT &p_coeff, Eigen::Vector4f &u, Eigen::Vector4f &v) 
//  通过平面参数p_coeff 获取u、v向量,用于isBoundaryPoint函数参数获取。
void  setInputNormals (const PointCloudNConstPtr &normals) 
//  设置输入点云的法线,normals为指向输入点云法线的指针引用。
virtual void  setInputCloud (const PointCloudConstPtr &cloud) 
//  设置投影所需的点云,cloud为指向输入点云的指针引用。  


5.Class pcl::CRHEstimation< PointInT, PointNT, PointOutT >

类CRHEstimation实现摄像头旋转直方图描述子CRH (Camera Roll Histogram)计算算法,利用该算子主要进行刚体对象的位姿估计,详细见文献(CAD -Model Recognition and 6DOF Pose Estimation Using 3D Cues)。

#include <pcl/features/crh.h>
CRHEstimation () 
//  构造函数
void  setViewPoint (float vpx, float vpy, float vpz) 
//  设置计算算子时需要的视点,vpx,vpy,xpz分别为视点的三维坐标。
void  getViewPoint (float &vpx, float &vpy, float &vpz) 
//  获得计算算子时需要的视点,vpx,vpy,xpz分别存储视点的三维坐标。
void  setCentroid (Eigen::Vector4f &centroid) 
//  设置中心点坐标,centroid为中心点坐标的引用。
void  setSearchMethod (const KdTreePtr &tree) 
//  设置内部计算时需要的搜索方法,是kd-tree或者octree等的对象指针。
void  compute (PointCloudOut &output) 
//  output存储计算得到的CRH描述子,建议PointCloudOut为pcl:: Histogram

6.Class pcl::CVFHEstimation< PointInT, PointNT, PointOutT >

类CVFHEstimation实现聚类视点直方图CVFH(Clustered Viewpoint Feature Histogram)描述子的计算,该描述算子主要是针对解决有残缺的点云识别问题而提出的,详细见文献(CAD - Model Recognition and 6DOF Pose Estimation Using 3D Cues)。

#include <pcl/features/cvfh.h>
CVFHEstimation () 
//  空构造函数
void  filterNormalsWithHighCurvature (const pcl::PointCloud< PointNT > &cloud, std::vector< int > &indices_to_use, std::vector< int > &indices_out, std::vector< int > &indices_in, float threshold) 
//  过滤掉曲率大于设定阈值的点,其中参数cloud和indices_to_use限定需要处理的点云,indices_out存储不符合曲率要求的点索引,indices_in存储符合曲率要求的点索引, threshold为设定的曲率值。
void  setViewPoint (float vpx, float vpy, float vpz) 
//  设置视点坐标。
void  setRadiusNormals (float radius_normals) 
//  设置内部用来计算估计法线时所用的半径,radius_normals取值过大过小都影响法线估计的效果,具体可根据用户的应用尺度要求灵活采用。
void  getViewPoint (float &vpx, float &vpy, float &vpz) 
//  获取视点坐标。
void  getCentroidClusters (std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > &centroids) 
//  获取用来计算CVFH时每个稳定区域的质心点。
void  getCentroidNormalClusters (std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > &centroids) 
//  获取用来计算CVFH时每个稳定区域的质心点法向量。
void  setClusterTolerance (float d) 
//  设置聚类时,归为一类的欧式距离最大值。
void  setEPSAngleThreshold (float d) 
//  设置聚类时,归为一类的两法线之间夹角最大值。
void  setCurvatureThreshold (float d) 
//  设置聚类前,需要过滤高曲率点时所用的,曲率上限阈值。
void  setMinPoints (size_t min) 
//  设置聚类时,作为一类的点数的最小值,聚类所得类的点数目小于该值的后序计算不考虑。
void  setNormalizeBins (bool normalize) 
//  设置是否对CVFH进行归一化。
void  compute (PointCloudOut &output) 
//  计算输出CVFH描述子到output, 默认output的点类型为pcl:: VFHSignature308。



7.Class pcl::ESFEstimation< PointInT, PointOutT >

类ESFEstimation实现了ESF(Ensemble of Shape Function) 描述子,该描述子主要用于实时对三维场景中的点云模型进行分类而提出的,详细参考(Ensemble ofShape Functions for 3D Object Classification)。

#include <pcl/features/esf.h>
ESFEstimation () 
//  空构造函数
void  compute (PointCloudOut &output) 
//  计算ESF描述子,output点类型为pcl: : ESFSignature640。
void  setRadiusSearch (double radius) 
//  设置内部计算需要搜索时用的近邻半径。
void  setKSearch (int k) 
//  设置内部计算需要搜索时用的k近邻个数。  


8.Class pcl::FeatureWithLocalReferenceFrames< PointInT, PointRFT >

类FeatureWithLocalReferenceFrames为所用需要局部坐标系的特征描述子的基类,目前是为了向后兼容,将来该类会被删除,用class pcl:: Feature< PointInT, PointOutT >代替。

9.Class pcl::FPFHEstimation< PointInT, PointNT, PointOutT >

类FPFHEstimation实现了FPFH(Fast Point Feature Histogram)描述子计算算法,该算子是局部点特征描述子之一,计算速度简单、并且不失描述性,主要针对点云配准中求对应点对而提出,后续实例中也讲到FPFH、SPFH概念,详细见Fast .Point Feature Histograms (FPFH) for 3D Registration。

#include <pcl/features/fpfh.h>
FPFHEstimation () 
//  空构造函数
bool  computePairFeatures (const pcl::PointCloud< PointInT > &cloud, const pcl::PointCloud< PointNT > &normals, int p_idx, int q_idx, float &f1, float &f2, float &f3, float &f4) 
//  计算两个点之间的3个角度特征和一个距离特征,其中cloud为包含计算点的点云,normals为归一化后的两个点对应的法向量,p_idx 为第一个点的索引,q_idx为第二个点的索引,其他几个参数分别存储计算所得的3个角特征和一个距离特征。  
void  computePointSPFHSignature (const pcl::PointCloud< PointInT > &cloud, const pcl::PointCloud< PointNT > &normals, int p_idx, int row, const std::vector< int > &indices, Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3) 
//  基于邻域计算单个点的SPFH(Simple Point Feature Histograms) 描述子,每对点有3个角特征,其中cloud和normals分别为点云和其对应的法线,p_idx为需要计算的点的索引,row为直方图参数的行,indices为近邻的索引向量,hist_f1、hist_f2、hist_f3对应3个统计特征直方图。
void  weightPointSPFHSignature (const Eigen::MatrixXf &hist_f1, const Eigen::MatrixXf &hist_f2, const Eigen::MatrixXf &hist_f3, const std::vector< int > &indices, const std::vector< float > &dists, Eigen::VectorXf &fpfh_histogram) 
//  权重计算SPFH得到最终的FPFH描述子,其中hist_f1、hist_f2、hist_f3对应SPFH的3个统计特征直方图,indices对应邻域的索引,dists对应每个邻域的距离向量,fpfh_histogram 存储最终计算得到的FPFH描述子。
void  setNrSubdivisions (int nr_bins_f1, int nr_bins_f2, int nr_bins_f3) 
//  设置SPFH的统计区间个数。
void  getNrSubdivisions (int &nr_bins_f1, int &nr_bins_f2, int &nr_bins_f3) 
//  获得SPFH的统计区间个数。
void  compute (PointCloudOut &output) 
//  计算获得输入点云和法线对应的FPFH描述子,output的点类型为pcl::FPFHSignature33.

10.Class pcl::FPFHEstimationOMP< PointInT, PointNT, PointOutT >

类FPFHEstimationOMP为类FPFHEstimation的基于OpenMP的高性能并行实现。

11.Class pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >

类GFPFHEstimation实现GFPFH(Global Fast Point Feature Histogram) 描述子计算算法,该描述子为全局尺度描述子,针对三维场景中模型对象的分类而提出的。

#include <pcl/features/gfpfh.h>
GFPFHEstimation () 
//  空构造函数
void  setOctreeLeafSize (double size) 
//  设置内部计算使用八叉树时的叶子大小。
double  getOctreeLeafSize () 
//  获得内部计算使用八叉树时的叶子大小。
uint32_t  emptyLabel () const 
//  返回空标签值。
uint32_t  getNumberOfClasses () const 
//  获得根据FPFH描述子分类的数目。
void  setNumberOfClasses (uint32_t n) 
//  设置根据FPFH描述子分类的数目。
int  descriptorSize () const 
//  返回描述子大小。
void  setInputLabels (const PointCloudLConstPtr &labels) 
//  设置搜索需要点云对应的标签,这里注意,如果利用setSearchSurface函数设置了搜索点云,则标签就不是默认输入点云的标签,而是setSearchSurface设置的点云对应的标签。
void  setRadiusSearch (double radius) 
//  设置搜索紧邻时所使用的半径。
void  compute (PointCloudOut &output) 
//  计算GFPFH描述子,存储在output中。此处output类型为直方图类型,大小由用户根据需求指定。


12.Class pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >

类IntensityGradientEstimation实现强度梯度计算和管理,强度梯度的方向是指向强度下降最快的方向,其二阶矩表征下降的速率。

#include <pcl/features/intensity_gradient.h>
IntensityGradientEstimation () 
//  空构造函数
void  setNumberOfThreads (unsigned int nr_threads=0) 
//  设置计算时并行进行的线程数目。
void  setInputNormals (const PointCloudNConstPtr &normals) 
//  设置输入点云对应的法向量。
void  setInputCloud (const PointCloudConstPtr &cloud) 
//  设置输入点云,cloud的点类型需要至少包括点坐标和强度。
void  compute (PointCloudOut &output) 
//  计算获取点云对应的强度梯度点类型,output类型来自于pcl::common::IntensityFieldAccessor< <PointInT>.

13.Class pcl::IntensitySpinEstimation< PointInT, PointOutT >

类IntensitySpinEstimation实现在强度域的旋转图像的计算算法,详细参考ASparse Texture Representation Using Local Affine Regions.

#include <pcl/features/intensity_spin.h>
IntensitySpinEstimation () 
//  空构造函数
void  computeIntensitySpinImage (const PointCloudIn &cloud, float radius, float sigma, int k, const std::vector< int > &indices, const std::vector< float > &squared_distances, Eigen::MatrixXf &intensity_spin_image) 
//  计算强度域的旋转图像,cloud指向含有坐标和强度值类型的点云,radius表示特征的半径,sigma设置内部进行高斯光滑直方图时所用的误差限,k为邻域个数,indices邻域对应点的索引,squared_distances为领域点到搜索点之间的距离平方,intensity_spin_image最终计算获取的强度旋转图像。  
void  setNrDistanceBins (size_t nr_distance_bins) 
//  设置强度旋转图像中距离维度的区间数目。
int  getNrDistanceBins () 
//  获得强度旋转图像中距离维度的区间数目。
void  setNrIntensityBins (size_t nr_intensity_bins) 
//  设置强度旋转图像中强度维度的区间数目。
int  getNrIntensityBins () 
//  获得强度旋转图像中强度维度的区间数目。
void  setSmoothingBandwith (float sigma) 
//  设置当构造旋转图像时,高斯平滑核的误差限。
float  getSmoothingBandwith () 
//  获得当构造旋转图像时,高斯平滑核的误差限。
void  computeFeature (PointCloudOut &output) 
//  计算获取点云对应的强度域描述符。   



14.Class pcl::MomentInvariantsEstimation< PointInT, PointOutT >

类MomentInvariantsEstimation实现对点云中每个点的不变矩的估计。

#include <pcl/features/moment_invariants.h>
MomentInvariantsEstimation () 
//  空构造函数
void  computePointMomentInvariants (const pcl::PointCloud< PointInT > &cloud, const std::vector< int > &indices, float &j1, float &j2, float &j3) 
//  利用cloud中indices索引向量指定的点集,计算3个不变矩,存储在j1、j2、j3中。
void  computePointMomentInvariants (const pcl::PointCloud< PointInT > &cloud, float &j1, float &j2, float &j3) 
 //  利用cloud中的点集,计算3个不变矩,存储在j1、j2、j3中。

15.Class pcl::Narf

类Narf实现了与归一化对齐径向特征NARF (Normal Aligned Radial Features)描述子相关的计算,NARF主要是针对三维场景中对象的识别而提出的描述子,详细请参考NARF: 3D Range Image Features for Object Recognition。

#include <pcl/features/narf.h>
Narf () 
//  空构造函数
Narf (const Narf &other) 
//  复制构造函数
~Narf () 
//  析构函数
const Narf &  operator= (const Narf &other) 
//  定义运算符=
bool  extractFromRangeImage (const RangeImage &range_image, const Eigen::Affine3f &pose, int descriptor_size, float support_size, int surface_patch_world_size=NARF_DEFAULT_SURFACE_PATCH_PIXEL_SIZE) 
// 该函数实现从深度图像提取NARF,其中range_image为深度图像,pose决定特征的坐标系统,descriptor_size指定描述子大小,support_size指定特征描述子支持的空间实际大小,surface_patch_world_size 面片的大小。
bool  extractFromRangeImage (const RangeImage &range_image, float x, float y, int descriptor_size, float support_size) 
 // x、y指定感兴趣点图像坐标系的坐标,其他同上函数。
bool  extractFromRangeImage (const RangeImage &range_image, const InterestPoint &interest_point, int descriptor_size, float support_size) 
//  interest_point指定感兴趣点,其他同上函数。
bool  extractFromRangeImage (const RangeImage &range_image, const Eigen::Vector3f &interest_point, int descriptor_size, float support_size) 
//  interest_point指定感兴趣点的三维坐标,其他同上函数。
bool  extractFromRangeImageWithBestRotation (const RangeImage &range_image, const Eigen::Vector3f &interest_point, int descriptor_size, float support_size) 
//  同上,但在计算时选择了合适的参数,结果具有旋转不变性。
void  getRotations (std::vector< float > &rotations, std::vector< float > &strengths) const 
  
void  getRotatedVersions (const RangeImage &range_image, const std::vector< float > &rotations, std::vector< Narf *> &features) const 
  
float  getDescriptorDistance (const Narf &other) const 
//  计算描述符距离,[0,1]中的值为0表示相同,每个单元格大于最大距离为1。
int  getNoOfBeamPoints () const 
//  获得梯度星上用来计算描述符数量。How many points on each beam of the gradient star are used to calculate the descriptor? More...
void  copyToNarf36 (Narf36 &narf36) const 
//  将描述符和姿势复制到点struct Narf36。
void  saveBinary (const std::string &filename) const 
//  用二进制格式写入文件
void  saveBinary (std::ostream &file) const 
//  用二进制格式写入输出流
void  loadBinary (const std::string &filename) 
//  从二进制文件中读取
void  loadBinary (std::istream &file) 
//  从输入流中读取
bool  extractDescriptor (int descriptor_size) 
//  从已设置的其他成员创建描述符。Create the descriptor from the already set other members. More...
const float *  getDescriptor () const 
//  获得描述符。Getter (const) for the descriptor. More...
float *  getDescriptor () 
//  获得描述符。Getter for the descriptor. More...
const int &  getDescriptorSize () const 
//  获得描述符的长度。Getter (const) for the descriptor length. More...
int &  getDescriptorSize () 
//  获得描述符的长度。Getter for the descriptor length. More...
const Eigen::Vector3f &  getPosition () const 
//  获得描述符的位置。Getter (const) for the position. More...
Eigen::Vector3f &  getPosition () 
//  获得描述符的位置。Getter for the position. More...
const Eigen::Affine3f &  getTransformation () const 
//  获得描述符的六*度位姿。Getter (const) for the 6DoF pose. More...
Eigen::Affine3f &  getTransformation () 
//  获得描述符的六*度位姿。Getter for the 6DoF pose. More...
const int &  getSurfacePatchPixelSize () const 
//  获得用于曲面面片的像素大小(仅一维)。Getter (const) for the pixel size of the surface patch (only one dimension) More...
int &  getSurfacePatchPixelSize () 
//  获得用于曲面面片的像素大小(仅一维)。Getter (const) for the pixel size of the surface patch (only one dimension) More...
const float &  getSurfacePatchWorldSize () const 
//  获得曲面面片的世界大小。Getter (const) for the world size of the surface patch. More...
float &  getSurfacePatchWorldSize () 
//  获得曲面面片的世界大小。Getter for the world size of the surface patch. More...
const float &  getSurfacePatchRotation () const 
//  获取曲面片旋转的量。Getter (const) for the rotation of the surface patch. More...
float &  getSurfacePatchRotation () 
//  获取曲面片旋转的量。Getter for the rotation of the surface patch. More...
const float *  getSurfacePatch () const 
//  获取曲面片。Getter (const) for the surface patch. More...
float *  getSurfacePatch () 
//  获取曲面片。Getter for the surface patch. More...
void  freeSurfacePatch () 
//  擦除曲面片并释放内存。Method to erase the surface patch and free the memory. More...
void  setDescriptor (float *descriptor) 
//  设置描述符。Setter for the descriptor. More...
void  setSurfacePatch (float *surface_patch) 
//  设置曲面片。Setter for the surface patch. More... 


16.Class pcl::NarfDescriptor Class

类NarfDescriptor实现计算NARF描述子。

#include <pcl/features/narf_descriptor.h>
NarfDescriptor (const RangeImage *range_image=NULL, const std::vector< int > *indices=NULL) 
//  构造函数
virtual  ~NarfDescriptor () 
//  析构函数
void  setRangeImage (const RangeImage *range_image, const std::vector< int > *indices=NULL) 
//  设置输入深度图像。
void  compute (PointCloudOut &output) 
//  计算描述子,output类型为Narf36。
Parameters &  getParameters () 
//  获取对参数结构的引用。Get a reference to the parameters struct. More... 


17.Class pcl::NormalEstimation< PointInT, PointOutT >

类NormalEstimation实现对点云的法线进行估计。

#include <pcl/features/normal_3d.h>
NormalEstimation () 
//  空构造函数
virtual  ~NormalEstimation () 
//  空析构函数
bool  computePointNormal (const pcl::PointCloud< PointInT > &cloud, const std::vector< int > &indices, Eigen::Vector4f &plane_parameters, float &curvature) 
//  给定cloud和indices指定点集,通过最小二乘拟合出对应点平面,plane_parameters来存储平面参数,curvature测度点集对应曲面的曲率。
bool  computePointNormal (const pcl::PointCloud< PointInT > &cloud, const std::vector< int > &indices, float &nx, float &ny, float &nz, float &curvature) 
//  给定cloud和indices指定点集,通过最小二乘拟合出对应点平面,nx, ny, nz来存储平面参数,curvature测度点集对应曲面的曲率。  
virtual void  setInputCloud (const PointCloudConstPtr &cloud) 
//  设置输入点云。
void  setViewPoint (float vpx, float vpy, float vpz) 
//  设置视点,用来排除估计的法线方向的二义性。
void  getViewPoint (float &vpx, float &vpy, float &vpz) 
//  获得视点坐标。
void  useSensorOriginAsViewPoint () 
//  设置是否利用原始点云获取设备的获取原点作为视点,用来排除估计的法线方向的二义性。
void  compute (PointCloudOut &output) 
//  计算输出点云法线,output类型为pcl::Normal,每个元素为四元组,前三个保存法线信息,最后一个保存曲率。

18.Class pcl::NormalEstimationOMP< PointInT, PointOutT >

类NormalEstimationOMP为类NormalEstimation 基于OpenMP的并行实现。

19.Class pcl::PFHEstimation< PointInT, PointNT, PointOutT >

类PFHEstimation实现了点特征直方图PFH(Point Feature Histogram)描述子的计算算法,PFH是针对点云对齐配准而提出的描述子,详细参考后面实例中讲解或者文献Aligning Point Cloud Views using Persistent Feature Histograms。

#include <pcl/features/pfh.h>
PFHEstimation () 
//  空构造函数
void  setMaximumCacheSize (unsigned int cache_size) 
//  设置最大缓存大小。
unsigned int  getMaximumCacheSize () 
//  获得最大缓存大小。
void  setUseInternalCache (bool use_cache) 
//  设置是否内部管理删除冗余的缓存占用。
bool  getUseInternalCache () 
//  获得是否内部管理删除冗余的缓存占用的布尔值。
bool  computePairFeatures (const pcl::PointCloud< PointInT > &cloud, const pcl::PointCloud< PointNT > &normals, int p_idx, int q_idx, float &f1, float &f2, float &f3, float &f4) 
//  计算一对点对应的四元组特征值,cloud为包含点对的点云,normals对应法线,p_idx指定第一个点的索引,q_idx指定第二个点索引,其他四个参数存储四元组特征值。
void  computePointPFHSignature (const pcl::PointCloud< PointInT > &cloud, const pcl::PointCloud< PointNT > &normals, const std::vector< int > &indices, int nr_split, Eigen::VectorXf &pfh_histogram) 
//  计算某个点的PFH,cloud为计算所需点集所在的点云对象,normals为点云对应法线,indices为计算时查询点对应的邻域索引,nr_split每个特征值的区间个数,pfh_histogram存储最终的PFH描述子。
void  compute (PointCloudOut &output) 
//  计算给定点云中每个点的PFH描述子,存储在output中,output点类型为pcl::PF HSignature125。


20.Class pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >

类PrincipalCurvaturesEstimation实现对主曲率的估计。

#include <pcl/features/principal_curvatures.h>
PrincipalCurvaturesEstimation () 
//  构造函数
void  computePointPrincipalCurvatures (const pcl::PointCloud< PointNT > &normals, int p_idx, const std::vector< int > &indices, float &pcx, float &pcy, float &pcz, float &pc1, float &pc2) 
//  通过给定点及其法线的所确定的切平面进行PCA分析,得到主曲率,以及最大最小特征值。其中normals为指定点云及其法线,p_idx 为指定的查询点,通过该点进行最小二乘拟合平面的估计,indices计算时涉及到的近邻点索引向量,pex、pcy、pcz、pcl、pc2,分别为在xyz三个方向上的主曲率,以及最大最小特征值。
void  compute (PointCloudOut &output) 
//  计算输入点云及法线的主曲率,存储在output中,其中output的点类型为pcl:PrincipalCurvatures。


22.Class pcl::RIFTEstimation< PointInT, GradientT, PointOutT >

类RIFTEstimation实现RIFT(Rotation Invariant Feature Transform)描述子的相关计算,其是为描述局部完整外观而提出的描述子,主要用于图像分类与检索,是SIFT的一般化,具有旋转不变性。

#include <pcl/features/rift.h>
RIFTEstimation () 
//  空构造函数
void  setInputGradient (const PointCloudGradientConstPtr &gradient) 
//  设置梯度数据。
PointCloudGradientConstPtr  getInputGradient () const 
//  获得梯度数据。
void  setNrDistanceBins (int nr_distance_bins) 
//  设置距离维度的区间数目。
int  getNrDistanceBins () const 
//  获得距离维度的区间数目。
void  setNrGradientBins (int nr_gradient_bins) 
//  设置梯度维度的区间数目。
int  getNrGradientBins () const 
//  获得梯度维度的区间数目。
void  computeRIFT (const PointCloudIn &cloud, const PointCloudGradient &gradient, int p_idx, float radius, const std::vector< int > &indices, const std::vector< float > &squared_distances, Eigen::MatrixXf &rift_descriptor) 
//  计算RITF描述子,其中,cloud为输入点云,gradient为点云中每个点对应的强度梯度,p_idx为需要计算的查询点,radius设置RIFT描述子描述空间的半径,indices近邻的索引,squared_distances查询点与近邻之间的距离平方,rift_descriptor存储查询点的RIFT描述子。

23.Class pcl::RSDEstimation< PointInT, PointNT, PointOutT >

类RSDEstimation实现RSD( Radius - based Surface Descriptor)描述子的估计算法,该描述子计算速度快于FPFH的局部描述子,详细参考文献[General 3DModelling of Novel Objects from a Single View]。

#include <pcl/features/rsd.h>
RSDEstimation () 
//  空构造函数
void  setNrSubdivisions (int nr_subdiv) 
//  设置距离特征的区间数。
int  getNrSubdivisions () const 
//  获得距离特征的区间数。
void  setPlaneRadius (double plane_radius) 
//  设置半径,在此小于此半径的拟合区域被认为是平面。
double  getPlaneRadius () const 
//  获得平面半径,在此小于此半径的拟合区域被认为是平面。
void  setKSearch (int) 
//  禁用要用于特征估计的k个最近邻数的设置。Disables the setting of the number of k nearest neighbors to use for the feature estimation. More...  
void  setSaveHistograms (bool save) 
//  设置是否自动保存直方图。
bool  getSaveHistograms () const 
//  获得是否自动保存直方图的布尔值。
boost::shared_ptr< std::vector< Eigen::MatrixXf, Eigen::aligned_allocator< Eigen::MatrixXf > > >  getHistograms () const 
//  返回指向所有点的全距离角度直方图列表的指针。Returns a pointer to the list of full distance-angle histograms for all points. More... 
void  compute (PointCloudOut &output) 
//  计算RSD描述子存储到output。


24.Class pcl::SHOTEstimationBase< PointInT, PointNT, PointOutT, PointRFT >

类SHOTEstimationBase实现SHOT ( Signature of Histograms of OrienTations)描述子计算算法,SHOT描述子是局部描述子,主要用于曲面模型匹配,详细参考文献[Unique Signatures of Histograms for Local Surface Description]。

#include <pcl/features/shot.h>
virtual  ~SHOTEstimationBase () 
//  空析构函数
virtual void  computePointSHOT (const int index, const std::vector< int > &indices, const std::vector< float > &sqr_dists, Eigen::VectorXf &shot)=0 
//  计算给定点的SHOT描述子,其中index为给定点,indices为给定点近邻索引向量,sqr_dists为近邻对应平方距离组成的向量,shot存储计算SHOT描述子结果。
virtual void  setLRFRadius (float radius) 
//  如果用户未设置局部参考坐标系,则设置用于局部参考坐标系估计的半径。  
virtual float  getLRFRadius () const 
//  获得用于局部参考坐标系估计的半径。  
void  setInputReferenceFrames (const PointCloudLRFConstPtr &frames) 
//  设置局部参考坐标系。
virtual void  setInputCloud (const PointCloudConstPtr &cloud) 
//  设置给定点云。
void  setInputNormals (const PointCloudNConstPtr &normals) 
//  设置给定点云对应的法线。
void  compute (PointCloudOut &output) 
//   计算输出点云中每个点的SHOT算子,output类型为pcl::SHOT.
  

25.Class pcl::SHOTEstimation< PointInT, PointNT, PointOutT, PointRFT >

26.Class pcl::SHOTEstimation< PointInXYZRGB, PointNT, PointOutT, PointRFT >

上面两个类分别实现了不同模板参数的SHOT算子估计算法,详细参考其父类SHOTEstimationBase说明。

27.Class pcl::SHOTLocalReferenceFrameEstimation< PointInT, PointOutT >

类SHOTLocalReferenceF rameEstimation实现对在计算SHOT算子时所需的局部参考坐标系的估计。

#include <pcl/features/shot_lrf.h
SHOTLocalReferenceFrameEstimation () 
//  构造函数
virtual  ~SHOTLocalReferenceFrameEstimation () 
//  空析构函数
virtual void  setInputCloud (const PointCloudConstPtr &cloud) 
//  设置给定点云。
void  compute (PointCloudOut &output) 
//  计算局部参考坐标系,output的类型为ReferenceFrame。


28.Class Class pcl::SHOTEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >

类SHOTEstimationOMP是SHOT算子基于OpenMP并行计算算法的实现,其接口详细参考类SHOTEstimation。

29.Class pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >

类SpinImageEstimation实现旋转图像(Spin image) 描述子计算算法,主要用于曲面匹配及3D对象识别领域,详细可参考本章开始对旋转图像概念的介绍。

#include <pcl/features/spin_image.h>
SpinImageEstimation (unsigned int image_width=8, double support_angle_cos=0.0, unsigned int min_pts_neighb=0) 
//  空白旋转图像描述子的构造函数
virtual  ~SpinImageEstimation () 
//  空析构函数
void  setImageWidth (unsigned int bin_count) 
//  设置旋转图像的分辨率。
void  setSupportAngle (double support_angle_cos) 
//  设置在支撑域内两个点法线之间角度余弦最小值。
void  setMinPointCountInNeighbourhood (unsigned int min_pts_neighb) 
//  设置在计算旋转图像时所用的近邻个数最小数目。
void  setInputNormals (const PointCloudNConstPtr &normals) 
//  此处normals必须是和setInputCloud中点云对应,不像其他基于法线的特征对应类的该函数,是与setSearchSurface设置的点云对应。
void  setRotationAxis (const PointNT &axis) 
//  设置整个点云的旋转轴。
void  setInputRotationAxes (const PointCloudNConstPtr &axes) 
//  设置每个点的旋转轴。
void  useNormalsAsRotationAxis () 
//  设置使用每个点法线作为旋转轴。
void  setAngularDomain (bool is_angular=true) 
//  设置是否采用角度域,默认为使用角度域。
void  setRadialStructure (bool is_radial=true) 
//  设置是否采用径向参考,默认为使用径向参考,否则使用二位平面参考。
void  compute (PointCloudOut &output) 
//  计算获得旋转图像描述子,output点类型默认为pel;:Histogram<153>,如果设置了旋转图像分辨率,维数需要做相应的调整。

30.Class pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >

类UniqueShapeContext实现唯一形状内容( Unique ShapeContext)描述子计算算法,针对3D模型的检索提出的,用于分类与识别,详细参考文献[Unique Shape Context for 3D data description]。

#include <pcl/features/usc.h>
UniqueShapeContext () 
//  构造函数
virtual  ~UniqueShapeContext () 
//  析构函数
size_t  getAzimuthBins () const 
//  获得方位维度区间数目。
size_t  getElevationBins () const 
//  获得高度维度区间数目。
size_t  getRadiusBins () const 
//  获得径向维度区间数目。
void  setMinimalRadius (double radius) 
//  设置搜索时用的最小半径。
double  getMinimalRadius () const 
//  获得搜索时用的最小半径。  
void  setPointDensityRadius (double radius) 
//  设置计算点云密度时所用的半径。
double  getPointDensityRadius () const 
//  获得计算点云密度时所用的半径。
void  setLocalRadius (double radius) 
//  设置局部参考坐标系时用的半径。
double  getLocalRadius () const 
//  获得局部参考坐标系时用的半径。
void  setInputReferenceFrames (const PointCloudLRFConstPtr &frames) 
//  设置输入点云的参考坐标系。
virtual void  setInputCloud (const PointCloudConstPtr &cloud) 
//  设置输入点云。
void  compute (PointCloudOut &output) 
//  计算获取USC描述子,output的点类型分两部分,第一部分存储局部参考坐标,第二部分存储特征向量。

31.Class pcl::VFHEstimation< PointInT, PointNT, PointOutT >

类VFHEstimation实现VFH( Viewpoint Feature Histogram) 描述子计算算法,该算子为全局描述子,可用于3D场景中对象的识别,后面实例中有概念的介绍或者详细可参考Fast 3D Recognition and Pose Using the Viewpoint Feature Historgram。

#include <pcl/features/vfh.h>
VFHEstimation () 
//  空构造函数
void  computePointSPFHSignature (const Eigen::Vector4f &centroid_p, const Eigen::Vector4f &centroid_n, const pcl::PointCloud< PointInT > &cloud, const pcl::PointCloud< PointNT > &normals, const std::vector< int > &indices) 
//  利用近邻来计算查询点的简单点特征直方图SPFH描述子,centroid_p为查询点,centroid_n为查询点法线,cloud为点云对象,normals为点云对象对应的法线,indices为查询点近邻索引。
void  setViewPoint (float vpx, float vpy, float vpz) 
//  设置视点。
void  getViewPoint (float &vpx, float &vpy, float &vpz) 
//  获得视点。
void  setUseGivenNormal (bool use) 
//  设置是否使用给定的法线。
void  setNormalToUse (const Eigen::Vector3f &normal) 
//  设置使用的法线。
void  setUseGivenCentroid (bool use) 
//  设置是否使用给定的中心点。
void  setCentroidToUse (const Eigen::Vector3f &centroid) 
//  设置使用的中心点。
void  setNormalizeBins (bool normalize) 
//  设置是否归一化统计直方图。
void  setNormalizeDistance (bool normalize) 
//  设置是否归一化距离。
void  setFillSizeComponent (bool fill_size) 
//  如果设置为true,则VFH的第四组特征会被填充。
void  compute (PointCloudOut &output) 
//  计算获取VFH描述子, output类型为pcl:: VFHSignature308,前面4X45的FPFH特征,后面128为与视点相关的统计特征。

32.features其他关键成员说明

#include <pcl/features/feature.hpp>
void  pcl::solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix, const Eigen::Vector4f &point, Eigen::Vector4f &plane_parameters, float &curvature) 
//  通过协方差矩阵来估计最小二乘平面参数和曲率,covariance_matrix为3X3协方差矩阵来确定平面法线方向,point为估计平面上一点,估计所得平面参数存储在plane_ parameters,curvature 为估计曲率。
#include <pcl/features/normal_3d.h>
template<typename PointT >  
bool  pcl::computePointNormal (const pcl::PointCloud< PointT > &cloud, Eigen::Vector4f &plane_parameters, float &curvature) 
//  计算给定点集cloud对应的最小二乘平面参数与曲率,分别存储在plane_parameters、curvature。
template<typename PointT >  
bool  pcl::computePointNormal (const pcl::PointCloud< PointT > &cloud, const std::vector< int > &indices, Eigen::Vector4f &plane_parameters, float &curvature) 
//  功能同上,只是利用点云cloud和点索引向量indices给定点集。
template<typename PointT , typename Scalar >  
void  pcl::flipNormalTowardsViewpoint (const PointT &point, float vp_x, float vp_y, float vp_z, Eigen::Matrix< Scalar, 4, 1 > &normal) 
//  通过视点调整法线的方向,使其指向视点。
template<typename PointT , typename Scalar >  
void  pcl::flipNormalTowardsViewpoint (const PointT &point, float vp_x, float vp_y, float vp_z, Eigen::Matrix< Scalar, 3, 1 > &normal) 
//  功能同上,但法线为三元组。
PCL_EXPORTS bool  pcl::computePairFeatures (const Eigen::Vector4f &p1, const Eigen::Vector4f &n1, const Eigen::Vector4f &p2, const Eigen::Vector4f &n2, float &f1, float &f2, float &f3, float &f4) 
//  计算给定两个点之间的4个特征值(三个角特征、一个距离特征)。p1、p2为给定两个点坐标,n1、n2为给定两个点对应的法线,f1~f4存储计算结果。



上一篇:aloam中的ceres-solver


下一篇:下载附件时防止连点