PCL点云使用贪婪三角化进行曲面重构

一、PCL点云平滑和法线估计

题目:https://mp.weixin.qq.com/s?__biz=MzIxOTczOTM4NA==&mid=2247486705&idx=1&sn=ca333d7bb12b7c226270e98d0003a789&chksm=97d7e966a0a06070a8dba605966016d227d7a6cad786498070d9e1b8cea8747470a4840257fd&scene=21#wechat_redirect

/****************************
 * 题目:给定一个融合后的点云,已经对其进行下采样和滤波(代码已给)。
 * 请对其进行平滑(输出结果),然后计算法线,并讲法线显示在平滑后的点云上(提供截图)。
 *
* 本程序学习目标:
 * 熟悉PCL的平滑、法线计算、显示,为网格化做铺垫。
 *
 * 公众号:计算机视觉life。发布于公众号旗下知识星球:从零开始学习SLAM
 * 时间:2018.12
****************************/
#include <pcl/point_types.h>
#include <pcl/io/io.h>
#include <pcl/io/pcd_io.h>
#include <pcl/visualization/cloud_viewer.h>
#include <pcl/filters/radius_outlier_removal.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/filters/statistical_outlier_removal.h>
#include <pcl/surface/mls.h>
#include <pcl/features/normal_3d.h>

typedef pcl::PointXYZRGB PointT;

int main(int argc, char** argv)
{

	// Load input file
	pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>);
    pcl::PointCloud<PointT>::Ptr cloud_downSampled(new pcl::PointCloud<PointT>);
	pcl::PointCloud<PointT>::Ptr cloud_filtered(new pcl::PointCloud<PointT>);
	pcl::PointCloud<PointT>::Ptr cloud_smoothed(new pcl::PointCloud<PointT>);
	if (pcl::io::loadPCDFile("./fusedCloud.pcd", *cloud) == -1)
    {
        cout << "点云数据读取失败!" << endl;
    }

    std::cout << "Orginal points number: " << cloud->points.size() << std::endl;

    // 下采样,同时保持点云形状特征
    pcl::VoxelGrid<PointT> downSampled;  //创建滤波对象
    downSampled.setInputCloud (cloud);            //设置需要过滤的点云给滤波对象
    downSampled.setLeafSize (0.01f, 0.01f, 0.01f);  //设置滤波时创建的体素体积为1cm的立方体
    downSampled.filter (*cloud_downSampled);           //执行滤波处理,存储输出
    std::cout<<"cloud_downSampled: " << cloud_downSampled->size()<<std::endl;

    pcl::io::savePCDFile ("./downsampledPC.pcd", *cloud_downSampled);

	// 统计滤波
	pcl::StatisticalOutlierRemoval<PointT> statisOutlierRemoval;       //创建滤波器对象
    statisOutlierRemoval.setInputCloud (cloud_downSampled);            //设置待滤波的点云
    statisOutlierRemoval.setMeanK (50);                                //设置在进行统计时考虑查询点临近点数
    statisOutlierRemoval.setStddevMulThresh (3.0);                     //设置判断是否为离群点的阀值:均值+1.0*标准差
    statisOutlierRemoval.filter (*cloud_filtered);                     //滤波结果存储到cloud_filtered

    std::cout << "cloud_filtered: " << cloud_filtered->size()<<std::endl;
    pcl::io::savePCDFile ("./filteredPC.pcd", *cloud_filtered);
	// ----------------------开始你的代码--------------------------//
	// 请参考PCL官网实现以下功能
	// 对点云重采样
	pcl::search::KdTree<PointT>::Ptr treeSampling (new pcl::search::KdTree<PointT>);
	pcl::PointCloud<PointT> mls_point;
	pcl::MovingLeastSquares<PointT,PointT> mls;
	mls.setComputeNormals(false);
	mls.setInputCloud(cloud_filtered);
	mls.setPolynomialOrder(2);
	mls.setPolynomialFit(false);
	mls.setSearchMethod(treeSampling);
	mls.setSearchRadius(0.05);
	mls.process(mls_point);


    // 输出重采样结果
    cloud_smoothed = mls_point.makeShared();
    std::cout<<"cloud_smoothed: "<<cloud_smoothed->size() <<std::endl;

    //save cloud_smoothed
    pcl::io::savePCDFileASCII("cloud_smoothed.pcd",*cloud_smoothed);
 

	// 法线估计
	pcl::NormalEstimation<PointT,pcl::Normal> normalEstimation;
	normalEstimation.setInputCloud(cloud_smoothed);
	pcl::search::KdTree<PointT>::Ptr tree(new pcl::search::KdTree<PointT>);
	normalEstimation.setSearchMethod(tree);
	pcl::PointCloud<pcl::Normal>::Ptr normals(new pcl::PointCloud<pcl::Normal>);
	normalEstimation.setKSearch(10);
	normalEstimation.compute(*normals);
	std::cout<<"normals: "<<normals->size()<<", "<<"normals fields: "<<pcl::getFieldsList(*normals)<<std::endl;
	pcl::io::savePCDFileASCII("normals.pcd",*normals);

	// ----------------------结束你的代码--------------------------//
	// 显示结果
    boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer (new pcl::visualization::PCLVisualizer ("PCL Viewer"));
    viewer->setBackgroundColor (0, 0, 0);
    pcl::visualization::PointCloudColorHandlerRGBField<PointT> rgb(cloud_smoothed);//color
    viewer->addPointCloud<PointT> (cloud_smoothed, rgb, "smooth cloud");
    viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "smooth cloud");
    viewer->addPointCloudNormals<PointT, pcl::Normal> (cloud_smoothed, normals, 10, 0.1, "normals");

    viewer->initCameraParameters ();

    while (!viewer->wasStopped ())
    {
        viewer->spinOnce (100);
        boost::this_thread::sleep (boost::posix_time::microseconds (100000));
    }

    return 0;
}

1、控制法线显示的数目:

    viewer->addPointCloudNormals<PointT, pcl::Normal> (cloud_smoothed, normals, 10, 0.1, "normals");

   10,就是每10个法线显示一个。

   0.1,就是每个法线的长度。

2、获取PointCloud的Fields

pcl::getFieldsList(*normals)

二、贪婪三角化投影曲面重建

计算流程:点云输入 --> 下采样 --> 统计滤波去除离群点 --> mls移动最小二乘法进行平滑处理 --> 对平滑后的点云进行法线估计(有向点云) --> 将法线和平滑后的点云的Fields拼接在一起 --> 贪婪三角化 -->显示输出

/****************************
 * 题目:给定一个融合后的点云,已经对其进行下采样和滤波(代码已给)。
 * 请对其进行平滑(输出结果),然后计算法线,并讲法线显示在平滑后的点云上(提供截图)。
 *
* 本程序学习目标:
 * 熟悉PCL的平滑、法线计算、显示,为网格化做铺垫。
 *
 * 公众号:计算机视觉life。发布于公众号旗下知识星球:从零开始学习SLAM
 * 时间:2018.12
****************************/
#include <pcl/point_types.h>
#include <pcl/io/io.h>
#include <pcl/io/pcd_io.h>
#include <pcl/visualization/cloud_viewer.h>
#include <pcl/filters/radius_outlier_removal.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/filters/statistical_outlier_removal.h>
#include <pcl/surface/mls.h>
#include <pcl/features/normal_3d.h>

#include <pcl/surface/gp3.h>

typedef pcl::PointXYZ PointT;

int main(int argc, char** argv)
{

	// Load input file
	pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>);
    pcl::PointCloud<PointT>::Ptr cloud_downSampled(new pcl::PointCloud<PointT>);
	pcl::PointCloud<PointT>::Ptr cloud_filtered(new pcl::PointCloud<PointT>);
	pcl::PointCloud<PointT>::Ptr cloud_smoothed(new pcl::PointCloud<PointT>);
	if (pcl::io::loadPCDFile("./fusedCloud.pcd", *cloud) == -1)
    {
        cout << "点云数据读取失败!" << endl;
    }

    std::cout << "Orginal points number: " << cloud->points.size() << std::endl;

    // 下采样,同时保持点云形状特征
    pcl::VoxelGrid<PointT> downSampled;  //创建滤波对象
    downSampled.setInputCloud (cloud);            //设置需要过滤的点云给滤波对象
    downSampled.setLeafSize (0.01f, 0.01f, 0.01f);  //设置滤波时创建的体素体积为1cm的立方体
    downSampled.filter (*cloud_downSampled);           //执行滤波处理,存储输出
    std::cout<<"cloud_downSampled: " << cloud_downSampled->size()<<std::endl;

    pcl::io::savePCDFile ("./downsampledPC.pcd", *cloud_downSampled);

	// 统计滤波
	pcl::StatisticalOutlierRemoval<PointT> statisOutlierRemoval;       //创建滤波器对象
    statisOutlierRemoval.setInputCloud (cloud_downSampled);            //设置待滤波的点云
    statisOutlierRemoval.setMeanK (50);                                //设置在进行统计时考虑查询点临近点数
    statisOutlierRemoval.setStddevMulThresh (3.0);                     //设置判断是否为离群点的阀值:均值+1.0*标准差
    statisOutlierRemoval.filter (*cloud_filtered);                     //滤波结果存储到cloud_filtered

    std::cout << "cloud_statical_filtered: " << cloud_filtered->size()<<std::endl;
    pcl::io::savePCDFile ("./filteredPC.pcd", *cloud_filtered);
	// ----------------------开始你的代码--------------------------//
	// 请参考PCL官网实现以下功能
	// 对点云重采样
	pcl::search::KdTree<PointT>::Ptr treeSampling (new pcl::search::KdTree<PointT>);
	pcl::PointCloud<PointT> mls_point;
	pcl::MovingLeastSquares<PointT,PointT> mls;
	mls.setComputeNormals(false);
	mls.setInputCloud(cloud_filtered);
	mls.setPolynomialOrder(2);
	mls.setPolynomialFit(false);
	mls.setSearchMethod(treeSampling);
	mls.setSearchRadius(0.05);
	mls.process(mls_point);


    // 输出重采样结果
    cloud_smoothed = mls_point.makeShared();
    std::cout<<"cloud_smoothed: "<<cloud_smoothed->size() <<std::endl;

    //save cloud_smoothed
    pcl::io::savePCDFileASCII("cloud_smoothed.pcd",*cloud_smoothed);
 

	// 法线估计
	pcl::NormalEstimation<PointT,pcl::Normal> normalEstimation;
	normalEstimation.setInputCloud(cloud_smoothed);
	pcl::search::KdTree<PointT>::Ptr tree(new pcl::search::KdTree<PointT>);
	normalEstimation.setSearchMethod(tree);
	pcl::PointCloud<pcl::Normal>::Ptr normals(new pcl::PointCloud<pcl::Normal>);
	normalEstimation.setKSearch(10);
	normalEstimation.compute(*normals);
	std::cout<<"normals: "<<normals->size()<<", "<<"normals fields: "<<pcl::getFieldsList(*normals)<<std::endl;
	pcl::io::savePCDFileASCII("normals.pcd",*normals);

	//Triangle Projection
	pcl::PointCloud<pcl::PointNormal>::Ptr cloud_with_normals(new pcl::PointCloud<pcl::PointNormal>);
	pcl::concatenateFields(*cloud_smoothed,*normals,*cloud_with_normals);
	std::cout<<"cloud_with_normals fields: "<<pcl::getFieldsList(*cloud_with_normals)<<std::endl;

	pcl::io::savePCDFileASCII("cloud_with_normals.pcd",*cloud_with_normals);

	pcl::search::KdTree<pcl::PointNormal>::Ptr tree2(new pcl::search::KdTree<pcl::PointNormal>);
	tree2->setInputCloud(cloud_with_normals);

	pcl::GreedyProjectionTriangulation<pcl::PointNormal> gp3;
	pcl::PolygonMesh triangles;

	gp3.setSearchRadius(0.1);
	gp3.setMu(2.5);
	gp3.setMaximumNearestNeighbors(52);

	gp3.setMaximumAngle(2*M_PI/3);
	gp3.setMinimumAngle(M_PI/18);

	gp3.setMaximumSurfaceAngle(M_PI/4);
	gp3.setNormalConsistency(false);

	gp3.setInputCloud(cloud_with_normals);
	gp3.setSearchMethod(tree2);
	gp3.reconstruct(triangles);


	// ----------------------结束你的代码--------------------------//
	// 显示结果
    boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer (new pcl::visualization::PCLVisualizer ("PCL Viewer"));
    viewer->setBackgroundColor (0, 0, 0);
/*
    pcl::visualization::PointCloudColorHandlerRGBField<PointT> rgb(cloud_smoothed);//color
    viewer->addPointCloud<PointT> (cloud_smoothed, rgb, "smooth cloud");
    viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "smooth cloud");
    viewer->addPointCloudNormals<PointT, pcl::Normal> (cloud_smoothed, normals, 10, 0.1, "normals");
*/
    viewer->addPolygonMesh(triangles,"GPTriangle");
    viewer->addText("GPTriangle",0,0,"GPTriangle");
    viewer->initCameraParameters ();

    while (!viewer->wasStopped ())
    {
        viewer->spinOnce (100);
        boost::this_thread::sleep (boost::posix_time::microseconds (100000));
    }

    return 0;
}

参考:https://cloud.tencent.com/developer/article/1436518

可视化:

 重建效果图2:

几个需要注意的地方:

1、贪婪三角化算法必须要求点云是平滑的,且密度变化均匀(这也是上一步为什么要做一个平滑处理)。

2、 贪婪投影三角化要求输入的点云必须是有向点云,所以对平滑后的点云进行法向量估计,并且将其Fields拼接在一起

3、拼接Fields的时候函数

pcl::concatenateFields
只能接受PointXYZ类型的点云数据,对于平滑后的带有RGB信息的点云要将其以PointXYZ的类型读入。

4、重建结果显示是函数

viewer->addPolygonMesh(triangles,"GPTriangle");

 

  • 8
    点赞
  • 68
    收藏
    觉得还不错? 一键收藏
  • 打赏
    打赏
  • 8
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 8
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

打赏作者

Tech沉思录

点赞加投币,感谢您的资瓷~

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

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

打赏作者

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

抵扣说明:

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

余额充值