PCL:点云数据基于法线的边界提取(从最初的法线估计理论推导到最终的边界提取)
該邊界提取采用PCL庫里邊的方法,基于法線估計來實現(xiàn)的邊界檢測與提取:
首先從原始點云上計算出法線,再由法線結(jié)合數(shù)據(jù)估計出邊界。(這樣解釋還是特別抽像吧)
------------法線求解:(平面的法線是垂直于它的單位向量。在點云的表面的法線被定義為垂直于與點云表面相切的平面的向量。法線提供了關(guān)于曲面的曲率信息)
對點云數(shù)據(jù)集的每個點的法線估計,可以看作是對表面法線的近似推斷。(因此該表面的判斷就是你尋找的周圍幾個點或者半徑內(nèi)幾個點組成的平面,就是下述代碼中reforn這個參數(shù),該參數(shù)的設置一般設置為分辨率的10倍時,效果較好,主要是對于法線估計。鄰域半徑選擇太小了,噪聲較大,估計的法線就容易出錯,而搜索鄰域半徑設置的太大估計速度就比較慢。)
----------求解原理
確定表面一點法線的問題近似于估計表面的一個相切面法線的問題,因此轉(zhuǎn)換過來以后就變成一個最小二乘法平面擬合估計問題。
平面方程用法線式表示為:
為平面上點處法向量的方向余弦,|p|為原點到平面的距離。
? ? (此處a,b,c能夠構(gòu)成該平面的一個法向量n,后邊的約束條件三方和為1只是控制了法向量大小,并沒有改變方向,是為了下邊利用點到平面的距離公式時,控制分母為1簡化計算)
求平面方程即轉(zhuǎn)化為求四個參數(shù)。
將上式整理為: ? ? ? ? ? ? ? ? ? ? ?? (由該式子聯(lián)系求特征值特征向量可以想到,為特征值,即為對應的特征向量)
即轉(zhuǎn)化到了求解矩陣A的特征值與特征向量的問題,矩陣A即為n個點的協(xié)方差矩陣。即為該矩陣的一個特征向量。
//PCL中的NormalEstimation
#include <pcl/point_types.h>
#include <pcl/features/normal_3d.h>{pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);... read, pass in or create a point cloud ...// Create the normal estimation class, and pass the input dataset to itpcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> ne;ne.setInputCloud (cloud);// Create an empty kdtree representation, and pass it to the normal estimation object.// Its content will be filled inside the object, based on the given input dataset (as no other search surface is given).pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ> ());ne.setSearchMethod (tree);// Output datasetspcl::PointCloud<pcl::Normal>::Ptr cloud_normals (new pcl::PointCloud<pcl::Normal>);// Use all neighbors in a sphere of radius 3cmne.setRadiusSearch (0.03);// Compute the featuresne.compute (*cloud_normals);// cloud_normals->points.size () should have the same size as the input cloud->points.size ()*
}
OpenMP加速法線估計
PCL提供了表面法線估計的加速實現(xiàn),基于OpenMP使用多核/多線程來加速計算。 該類的名稱是pcl :: NormalEstimationOMP,其API與單線程pcl :: NormalEstimation 100%兼容。 在具有8個內(nèi)核的系統(tǒng)上,一般計算時間可以加快6-8倍。
include <pcl/point_types.h>
#include <pcl/features/normal_3d_omp.h>{pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);... read, pass in or create a point cloud ...// Create the normal estimation class, and pass the input dataset to itpcl::NormalEstimationOMP<pcl::PointXYZ, pcl::Normal> ne;ne.setNumberOfThreads(12); // 手動設置線程數(shù),否則提示錯誤ne.setInputCloud (cloud);// Create an empty kdtree representation, and pass it to the normal estimation object.// Its content will be filled inside the object, based on the given input dataset (as no other search surface is given).pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ> ());ne.setSearchMethod (tree);// Output datasetspcl::PointCloud<pcl::Normal>::Ptr cloud_normals (new pcl::PointCloud<pcl::Normal>);// Use all neighbors in a sphere of radius 3cmne.setRadiusSearch (0.03);// Compute the featuresne.compute (*cloud_normals);// cloud_normals->points.size () should have the same size as the input cloud->points.size ()*
}
上述完整的介紹了法線的估計過程,自認為只要有稍微的高數(shù)基礎應該都能看懂的哈哈
下邊接著開始,怎么根據(jù)求的法線來找邊界呢???
基于法線完成的邊界估計主要是利用各個法線方向之間的夾角來做的判斷(所以有個設置角度的閾值參數(shù))。(此處還是沒有太明白怎么根據(jù)法線夾角確定哪些點是邊界點,如有特別明白的可以下邊評論留言。)
對于邊界的估計就是這個函數(shù)boundEst.setRadiusSearch(re),參數(shù)re也設置為分辨率(此處的分辨率指的是點云的密度)的10倍,太小則內(nèi)部的很多點就都當成邊界點了。最后一個參數(shù)是邊界判斷時的角度閾值,默認值為PI/2,此處設置為PI/4,用戶也可以根據(jù)需要進行更改。
#include <iostream>
#include <pcl/console/parse.h>
#include <pcl/filters/extract_indices.h>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <boost/thread/thread.hpp>
#include <pcl/features/boundary.h>
#include <math.h>
#include <boost/make_shared.hpp>
#include <pcl/point_cloud.h>
#include <pcl/visualization/cloud_viewer.h>
#include <pcl/visualization/range_image_visualizer.h>
#include <pcl/features/normal_3d.h>
#include <pcl/filters/covariance_sampling.h>
#include <pcl/filters/normal_space.h>
#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/io/ply_io.h>
#include <pcl/filters/statistical_outlier_removal.h>
int estimateBorders(pcl::PointCloud<pcl::PointXYZI>::Ptr &cloud, float re, float reforn)
{pcl::PointCloud<pcl::Boundary> boundaries; //保存邊界估計結(jié)果pcl::BoundaryEstimation<pcl::PointXYZI, pcl::Normal, pcl::Boundary> boundEst; //定義一個進行邊界特征估計的對象pcl::NormalEstimation<pcl::PointXYZI, pcl::Normal> normEst; //定義一個法線估計的對象pcl::PointCloud<pcl::Normal>::Ptr normals(new pcl::PointCloud<pcl::Normal>); //保存法線估計的結(jié)果pcl::PointCloud<pcl::PointXYZI>::Ptr cloud_boundary(new pcl::PointCloud<pcl::PointXYZI>);normEst.setInputCloud(pcl::PointCloud<pcl::PointXYZI>::Ptr(cloud));normEst.setRadiusSearch(reforn); //設置法線估計的半徑//normEst.setKSearch(10);//表示計算點云法向量時,搜索的點云個數(shù)normEst.compute(*normals); //將法線估計結(jié)果保存至normals//輸出法線的個數(shù)std:cout << "reforn: " << reforn << std::endl;std::cerr << "normals: " << normals->size() << std::endl;boundEst.setInputCloud(cloud); //設置輸入的點云boundEst.setInputNormals(normals); //設置邊界估計的法線,因為邊界估計依賴于法線boundEst.setRadiusSearch(re); //設置邊界估計所需要的半徑,//這里的Threadshold為一個浮點值,可取點云模型密度的10倍boundEst.setAngleThreshold(M_PI / 4); //邊界估計時的角度閾值M_PI / 4 并計算k鄰域點的法線夾角,若大于閾值則為邊界特征點boundEst.setSearchMethod(pcl::search::KdTree<pcl::PointXYZI>::Ptr(new pcl::search::KdTree<pcl::PointXYZI>)); //設置搜索方式KdTreeboundEst.compute(boundaries); //將邊界估計結(jié)果保存在boundariesstd::cerr << "AngleThreshold: " << M_PI / 4 << std::endl;//輸出邊界點的個數(shù)std::cerr << "boundaries: " << boundaries.points.size() << std::endl;//存儲估計為邊界的點云數(shù)據(jù),將邊界結(jié)果保存為pcl::PointXYZ類型for (int i = 0; i < cloud->points.size(); i++){if (boundaries[i].boundary_point > 0){cloud_boundary->push_back(cloud->points[i]);}}pcl::PCDWriter writer;std::stringstream ss;ss << "boundary" << ".pcd";writer.write<pcl::PointXYZI>(ss.str(), *cloud_boundary, false);//可視化顯示原始點云與邊界提取結(jié)果boost::shared_ptr<pcl::visualization::PCLVisualizer> MView(new pcl::visualization::PCLVisualizer("邊界提取"));int v1(0);MView->createViewPort(0.0, 0.0, 0.5, 1.0, v1);MView->setBackgroundColor(0.3, 0.3, 0.3, v1);MView->addText("Raw point clouds", 10, 10, "v1_text", v1);int v2(0);MView->createViewPort(0.5, 0.0, 1, 1.0, v2);MView->setBackgroundColor(0.5, 0.5, 0.5, v2);MView->addText("Boudary point clouds", 80, 80, "v2_text", v2);MView->addPointCloud<pcl::PointXYZI>(cloud, "sample cloud", v1);MView->addPointCloud<pcl::PointXYZI>(cloud_boundary, "cloud_boundary", v2);MView->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1, 0, 0, "sample cloud", v1);MView->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 0, 1, 0, "cloud_boundary", v2);MView->addCoordinateSystem(1.0);MView->initCameraParameters();MView->spin();return 0;
}
int
main(int argc, char** argv)
{srand(time(NULL));float re, reforn;re = std::atof(argv[2]);reforn = std::atof(argv[3]);pcl::PointCloud<pcl::PointXYZI>::Ptr cloud_src(new pcl::PointCloud<pcl::PointXYZI>);pcl::io::loadPCDFile(argv[1], *cloud_src);//創(chuàng)建濾波器對象pcl::PointCloud<pcl::PointXYZI>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZI>);pcl::StatisticalOutlierRemoval<pcl::PointXYZI> sor;sor.setInputCloud(cloud_src);sor.setMeanK(100);//尋找每個點的50個最近鄰點sor.setStddevMulThresh(3.0);//一個點的最近鄰距離超過全局平均距離的一個標準差以上,就會舍棄sor.filter(*cloud_filtered);std::cout << "cloud_src: " << cloud_src->points.size() << std::endl;std::cout << "cloud_filtered: " << cloud_filtered->points.size() << std::endl;estimateBorders(cloud_src, re, reforn);return 0;
}
右鍵項目->屬性->在命令行輸入?yún)?shù):如下所示:(以上需要三個參數(shù))
結(jié)果如下:
? ? ? ? ? ? ? ? ? ? ? ?
s
總結(jié)
以上是生活随笔為你收集整理的PCL:点云数据基于法线的边界提取(从最初的法线估计理论推导到最终的边界提取)的全部內(nèi)容,希望文章能夠幫你解決所遇到的問題。
- 上一篇: 机器学习中的数学基础(4.1):支持向量
- 下一篇: 1数字图像获取:1.1图像数字化