PCL点云库入门——PCL库点云特征之边界点特征提取(BoundaryEstimation)

1、算法原理

        在点云数据模型中将围成模型轮廓的点称为边界点,也称为边界特征点。边界特征点包含大量的曲面信息,对曲面重建质量有着非常重要的作用,它们不仅是连接不同曲面区域的桥梁,还是模型几何形状和拓扑结构的关键体现。正确地识别和提取边界特征点,有助于准确还原物体的三维形态,提升曲面重建的精度和逼真度。因此,在点云数据处理过程中,对边界特征点的检测和分析显得尤为重要。

        BoundaryEstimation算法是PCL中用于点云边界估计的重要算法。该算法的核心原理基于点云数据的局部几何特性分析,旨在识别并提取出点云中的边界点。算法的具体步骤为:

        第1步:先用数据点PK邻域点估计一个局部平面,并将数据点PK邻域点投射到该平面上

        第2步:其次在K邻域中选取到数据点P最近点Qi,并作有向向量PQi,以向量PQi作为基准,分别计算出数据点PK个邻域点Qj的有向量PQj之间的夹角,得到夹角集合为:

 ,将得到的夹角集合重新按从小到大排列得到新的角度集合

,最后计算新角度集合S两相邻角度的差,公式为

找出两角度之差差中的最大θmax值;

        第3步:设定一个判断数据点P为边界点的阈值θTHθmax>θTH时认为数据点P为边界并且保留下来。阈值θTH的取值要根据点云空间分别情况而定,在点云边界平缓的区域,可以相应的设置小一些,在边界点尖锐特征信息点可以设置大一些。

2、主要的成员函数和变量

1、主要成员变量

    1)、将点标记为边界点角度阈值

 float angle_threshold_;

2、主要成员函数

    1)、判断当前点是否为边界点

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);

 2)、设置角度阈值

inline void
      setAngleThreshold (float angle)

3)、计算当前点切平面的坐标系

 inline void 
      getCoordinateSystemOnPlane (const PointNT &p_coeff, 
                                  Eigen::Vector4f &u, Eigen::Vector4f &v)

3、主要实现代码注解

1)、边界点检测

///1.边界点检测
/
template <typename PointInT, typename PointNT, typename PointOutT> bool
pcl::BoundaryEstimation<PointInT, PointNT, PointOutT>::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)
{
       return (isBoundaryPoint(cloud, cloud.points[q_idx], indices, u, v,  angle_threshold));
}
//
template <typename PointInT, typename PointNT, typename PointOutT> bool
pcl::BoundaryEstimation<PointInT, PointNT, PointOutT>::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)
{
       //邻域点小于3或者无效的点不能识别为边界点
       if (indices.size() < 3)
              return (false);
       if (!std::isfinite(q_point.x) || !std::isfinite(q_point.y) ||  !std::isfinite(q_point.z))
              return (false);
       
       ///计算查询点与它邻域点之间的夹角
       std::vector<float> angles(indices.size());
       float max_dif = FLT_MIN, dif;
       int cp = 0;
       for (const int& index : indices)
       {
              //邻域点无效点检测
              if (!std::isfinite(cloud.points[index].x) ||
                      !std::isfinite(cloud.points[index].y) ||
                      !std::isfinite(cloud.points[index].z))
                      continue;
              Eigen::Vector4f delta = cloud.points[index].getVector4fMap() -  q_point.getVector4fMap();
              if (delta == Eigen::Vector4f::Zero())
                      continue;
              //在切平面坐标系v,u方向上的投影的角度计算
              angles[cp++] = std::atan2(v.dot(delta), u.dot(delta)); // the angles are  fine between -PI and PI too
       }
       if (cp == 0)
              return (false);
       angles.resize(cp);
       //角度排序
       std::sort(angles.begin(), angles.end());
       // 计算两个连续角度之间的最大夹角差
       for (std::size_t i = 0; i < angles.size() - 1; ++i)
       {
              dif = angles[i + 1] - angles[i];
              if (max_dif < dif)
                      max_dif = dif;
       }
       // 计算最后一个和第一个的夹角差
       dif = 2 * static_cast<float> (M_PI) - angles[angles.size() - 1] + angles[0];
       if (max_dif < dif)
              max_dif = dif;
       // 根据计算的最大角度差和阈值判断是否为边界点
       return (max_dif > angle_threshold);
}
//

2)、边界点特征提取

template <typename PointInT, typename PointNT, typename PointOutT> void
pcl::BoundaryEstimation<PointInT, PointNT, PointOutT>::computeFeature(PointCloudOut&  output)
{
       //最近邻域搜索参数初始化
       std::vector<int> nn_indices(k_);
       std::vector<float> nn_dists(k_);
       //局部坐标系初始化
       Eigen::Vector4f u = Eigen::Vector4f::Zero(), v = Eigen::Vector4f::Zero();
       output.is_dense = true;
       // 稠密点云
       if (input_->is_dense)
       {
              // 执行每一个点
              for (std::size_t idx = 0; idx < indices_->size(); ++idx)
              {
                      //最近邻域搜索
                      if (this->searchForNeighbors((*indices_)[idx],  search_parameter_, nn_indices, nn_dists) == 0)
                      {
                             output.points[idx].boundary_point =  std::numeric_limits<std::uint8_t>::quiet_NaN();
                             output.is_dense = false;
                             continue;
                      }
               //获取切平面的坐标系
                      getCoordinateSystemOnPlane(normals_->points[(*indices_)[idx]],  u, v);
                      //根据角度阈值判断当前点是否为边界点
                      output.points[idx].boundary_point = isBoundaryPoint(*surface_,  input_->points[(*indices_)[idx]], nn_indices, u, v, angle_threshold_);
              }
       }
       else
       {
              // 执行每一个点
              for (std::size_t idx = 0; idx < indices_->size(); ++idx)
              {
                      //最近邻域搜索
                      if (!isFinite((*input_)[(*indices_)[idx]]) ||
                             this->searchForNeighbors((*indices_)[idx],  search_parameter_, nn_indices, nn_dists) == 0)
                      {
                             output.points[idx].boundary_point =  std::numeric_limits<std::uint8_t>::quiet_NaN();
                             output.is_dense = false;
                             continue;
                      }
                      //获取切平面的坐标系
                      getCoordinateSystemOnPlane(normals_->points[(*indices_)[idx]],  u, v);
                      //根据角度阈值判断当前点是否为边界点
                      output.points[idx].boundary_point = isBoundaryPoint(*surface_,  input_->points[(*indices_)[idx]], nn_indices, u, v, angle_threshold_);
              }
       }
}

4、实例代码

/*****************************************************************//**
 * \file   PCLBoundarymain.cpp
 * \brief  边界特征点检测
 * 
 * \author HP
 * \date   January 2025
 *********************************************************************/
#include <iostream>
#include <math.h>
#include <pcl/io/auto_io.h>
#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <pcl/features/normal_3d.h>
#include <pcl/features/boundary.h>
#include <pcl/kdtree/kdtree_flann.h>
void estimateBorders()
{
       //加载点云数据
       pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new  pcl::PointCloud<pcl::PointXYZRGB>());
       std::string fileName = "E:/fragment.pcd";
       pcl::io::load(fileName, *cloud);
       std::cout << "Cloud Size:" << cloud->points.size() << std::endl;
       
       pcl::NormalEstimation<pcl::PointXYZRGB, pcl::Normal> norEst;
       pcl::PointCloud<pcl::Normal>::Ptr normals(new pcl::PointCloud<pcl::Normal>);
       norEst.setInputCloud(cloud);
       norEst.setRadiusSearch(0.04);
       norEst.compute(*normals);
       
       //边界特征点提取
       pcl::BoundaryEstimation<pcl::PointXYZRGB, pcl::Normal, pcl::Boundary> boundEst;
       pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_boundary(new  pcl::PointCloud<pcl::PointXYZRGB>);
       boundEst.setInputCloud(cloud);
       boundEst.setInputNormals(normals);
       boundEst.setRadiusSearch(0.08);
       boundEst.setAngleThreshold(M_PI / 4);
       boundEst.setSearchMethod(pcl::search::KdTree<pcl::PointXYZRGB>::Ptr(new  pcl::search::KdTree<pcl::PointXYZRGB>));
       
       //保存边界结果
       pcl::PointCloud<pcl::Boundary> boundaries;
       boundEst.compute(boundaries);
       
       //保存边界点结果用于可视化
       for (int i = 0; i < cloud->points.size(); ++i)
       {
              if (boundaries[i].boundary_point > 0){
                      cloud_boundary->push_back(cloud->points[i]);
              }
       }
       boost::shared_ptr<pcl::visualization::PCLVisualizer> View(new  pcl::visualization::PCLVisualizer("点云库PCL从入门到精通案例"));
       //创建可视化窗口和设置窗口的背景颜色
       int v1(0);
       View->createViewPort(0.0, 0.0, 0.5, 1.0, v1);
       View->setBackgroundColor(0.3, 0.3, 0.3, v1);
       View->addText("clouds", 10, 10, "v1_text", v1);
       int v2(0);
       View->createViewPort(0.5, 0.0, 1, 1.0, v2);
       View->setBackgroundColor(0.5, 0.5, 0.5, v2);
       View->addText("Boudary", 10, 10, "v2_text", v2);
       
       //添加点云和边界点云
       View->addPointCloud<pcl::PointXYZRGB>(cloud, "cloud", v1);
       View->addPointCloud<pcl::PointXYZRGB>(cloud_boundary, "boundaryCloud", v2);
    
       //可视化点云属性
       View->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1, 0,  0, "cloud", v1);
       View->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 0, 1,  0, "boundaryCloud", v2);
       
       //添加坐标系
       View->addCoordinateSystem(0.5);
       View->initCameraParameters();
       View->spin();
       return ;
}
int
main(int argc, char** argv)
{
       estimateBorders();
       std::cout << "Hello PCL World!" << std::endl;
       std::system("pause");
       return 0;
}

结果展示:

        至此完成第十七节PCL库点云特征之边界点特征的学习,下一节我们将进入《PCL库中点云关键点之深度图提取边界》的学习。 这是年前的最后一篇了,提前祝福大家新春快乐,感谢大家的支持。

评论 3
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

点云SLAM

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值