零蚀
【🔗 PCL官网】
【kinect2 驱动安装官网】
关于pcl和opencv的vtk版本冲突解决请看 🔗 Opencv和Pcl关于VTK版本冲突(Macos)
- 目录
- 点云简介
- 前言(ubuntu安装pcl)
- Mac上点云库安装
- 点云的运用
- 点云的生成
- 点云的工具
- 点云数据
- 点云的原数据和类型转化
- 点云的基础算法
- kd tree
- octree
- 点云的滤波
- 滤波方法
- 降采样
- rm离群点(除噪)
- 点云简介
点云简介
-
前言
-
点云是三维空间中的点的集合 ,点云可以通过深度相机或者CAD进行获取,点云是表示多维点的数据结构,点云表示三维树句,在3D点云中,这些点通常代表采样的X,Y,Z集合坐标,当存在颜色值时,点云就成了4维数据了。【🔗 点云数据】
-
三维的点云模型如下【🔗 斯坦福著名的兔子模型】
-
PCL(Point Cloud Library)是用于2D/3D跨平台 处理的大型的开源C++编程库。它有着体量小,算法高效等好处,除了PCL还有一些open3D等点云库。PCL是ROS下斯坦福大学的博士开发的开源项目,主要应用于机器人的研究应用领域,算法模块在2011年独立出来。
-
Ubuntu点云库的安装
sudo apt-get update sudo apt-get install git build-essential linux-libc-dev sudo apt-get install cmake cmake-gui sudo apt-get install libusb-1.0-0-dev libusb-dev libudev-dev sudo apt-get install libflann1.8 libflann-dev sudo apt-get install libeigen3-dev sudo apt-get install libboost-all-dev sudo apt-get install mpi-default-dev openmpi-bin openmpi-common sudo apt-get install libpcap-dev # 因为这里是ubuntu20,所以vtk支持最小是vtk7 sudo apt-get install libvtk7.1p-qt libvtk7.1 libvtk7-dev sudo apt-get install vtk7 libvtk7-dev libvtk7-qt-dev sudo apt-get install libqhull* libgtest-dev sudo apt-get install freeglut3-dev pkg-config sudo apt-get install libxmu-dev libxi-dev sudo apt-get install mono-complete sudo apt-get install mono-complete sudo apt-get install mono-complete sudo apt-get install openjdk-8-jdk openjdk-8-jre sudo apt install pcl-tools
-
【🔗 qt安装地址】
-
Ubuntu kinect2相机驱动的安装,这是一个深度相机
git clone https://github.com/OpenKinect/libfreenect2.git sudo apt-get install build-essential cmake pkg-config sudo apt-get install libusb-1.0-0-dev sudo apt-get install beignet-dev sudo apt-get install libturbojpeg libjpeg-turbo8-dev sudo apt-get install libglfw3-dev sudo apt-get install opencl-headers sudo apt-get install doxygen sudo apt-get install libva-dev libjpeg-dev sudo apt-get install openni2-utils sudo apt-get install build-essential cmake pkg-config libturbojpeg libjpeg-turbo8-dev mesa-common-dev freeglut3-dev libxrandr-dev libxi-dev sudo apt-get install libturbojpeg0-dev cd libfreenect2/ cd libfreenect2/ && cd build # cmake .. 是默认系统路径 cmake .. -DCMAKE_INSTALL_PREFIX=/home/baicha/tri/libfreenect2/freenect2 make sudo make install # 配置设备的访问权限 sudo cp ../platform/linux/udev/90-kinect2.rules /etc/udev/rules.d/
-
Prtonect是驱动的协议,可以在build目录下执行
./bin/Protonect
可以打开深度相机的图像,左上是红外的相机捕获的内容,左下是RGB彩色图,右上是RGB+深度图,右下是深度图 -
这里如果我们的相机打不开,显示viewer有问题,我们看看我们ubuntu的软件更新中附加驱动里,有没有对应驱动。如果没有,我们需要安装一下显卡的驱动。
-
在安装kinect驱动点的时候,如果libusb有问题,需要如下安装
sudo apt-add- repository ppa:floe/libbusb sudo apt-get update sudo apt-get install libusb-1.0-0-dev
-
-
Mac上点云库安装
-
由于ubuntu下无法打开mac中的GPU驱动程序,所以kinect2的摄像头打开是一片黑的,在网上试了很多种方法之后,发现都不行,所以这里我集成了ros2,后续的ros开发都会在mac上,具体的见【🔗 NO.13 ROS 2 Foxy安装(Mac OS)】
-
根据github上的安装教程,cd到
libfreenect2/build
目录下执行bin/Protonect
我们可以看到摄像头的内容
- macos 安装pcl流程如下,省去安装一大堆的工具的麻烦。
brew install pcl sudo vi ~/.bash_profile export PATH=${PATH}:/usr/local/Cellar/pcl/1.11.1_7/pcl_viewer.app/Contents/MacOS source ~/.bash_profile # 测试 pcl_viewer xxx.pcd
-
点云的生成及运用
-
点云
- 点云的生成有很多种,可以用CAD,或是用深度的图像获取物体一个方向的点云,在运行点云程序前,导入点云库我发现了一个问题,当我在CMakeList中
find_package(PCL REQUIRED)
会出现New Boost version may have incorrect or missing dependencies and imported
等警告,非常难看。这个是cmake版本和这个boost不匹配(boost是pcl所要运用的库),这里我调用了外部的brew install cmake,但是搞笑的是我下载的最新的cmake是3.20,但是最新的clion(2021.1)只能支持cmake 3.19.x,所以我在2021版上换了cmake-3.19.8[🔗 cmake3.19.x下载地址](目前最新的boost需要3.19.5以上版本的cmake)。
# 安装cmake ./bootstrap make sudo make install # 路径 /usr/local/bin/cmake
- 上一个警告就没有了,然后我们运行
pcl::visualization::CloudViewer
代码会发现,不允许在主线程里
Terminating app due to uncaught exception 'NSInternalInconsistencyException', reason: 'NSWindow drag regions should only be invalidated on the Main Thread!'
- 解决这个问题的关键不是添加线程,而是CloudViewer里会调用NSWindow,这里MacOS这方面是有很多地方在running中禁止使用的,所以我们编译可以通过,但是运行就会报错,所以pcl给了两个方向,除了CloudViewer还有PCLVisualizer,这里需要用PCLVisualizer。
#include <thread> #include <pcl/io/io.h> #include <pcl/io/pcd_io.h> #include <pcl/visualization/pcl_visualizer.h> using namespace std; int main(int argc, char **argv) { // 创建pcl指针 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>); // 将点云图加载到指针 pcl::io::loadPCDFile("bunny.pcd", *cloud); // 构建视图 pcl::visualization::PCLVisualizer viewer("my_view"); // 添加点云视图 viewer.addPointCloud(cloud); viewer.spin(); return 0; }
-
点云的工具
-
pcl_viewer 的操作命令(mac)
- q 退出窗口
- 1 全体切换颜色
- 2 全体切换彩虹色(从左到右红到蓝)
- 3 全体切换彩虹色(从下到上红到蓝)
- 4 全体切换彩虹色(从上到下红到蓝)
- ctr z轴旋转
- shift 整体平移
- 先lock 然后com+shift+(+/-) 缩放
- j 数据&截图保存
- u 颜色尺度信息
- g 比例尺度信息
- l 终端显示几何颜色信息
- 点击获取点的索引值
pcl_viewer bunny.pcd -use_point_picking
,然后shift+左键
- 点云的可视化工具有两个,一个PCLVisualizer,一个CloudViewer。先来展示CloudViewer的用法(但这个在Mac上不好使)。
void oneOff(pcl::visualization::PCLVisualizer &viewer){ // 设置背景颜色 viewer.setBackgroundColor(1.0,0.5,1.0); pcl::PointXYZ point; point.x = 1; point.y=0; point.z=0; // 围绕point点创建球体 viewer.addSphere(point,0.5,"sphere",0) } void psycho(pcl::visualization::PCLVisualizer &viewer){ } int main(int argc, char **argv) { // 创建pcl指针 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>); // 将点云图加载到指针 pcl::io::loadPCDFile("bunny.pcd", *cloud); pcl::visualization::CloudViewer viewer("my_view"); // 初始化的时候构建一次比如这里创建了一个球体 viewer.runOnVisualizationThread(oneOff); // 刷新的时候会调用 viewer.runOnVisualizationThreadOnce(psycho); while(viewer.wasStopped()){ } return 0; }
- PCLVisualizer
#include <thread> #include <pcl/io/io.h> #include <pcl/io/pcd_io.h> #include <pcl/visualization/pcl_visualizer.h> using namespace std; int main(int argc, char **argv) { // 创建pcl指针 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>); // 将点云图加载到指针 pcl::io::loadPCDFile("bunny.pcd", *cloud); pcl::visualization::PCLVisualizer viewer("my_view"); // 普通加载 //viewer.addPointCloud(cloud); // 设置背景 viewer.setBackgroundColor(0.05, 0.05, 0.05, 0); // 添加点云指定颜色 pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> color(cloud,0,255,255); // 多块点云随机定义 颜色pcl::visualization::PointCloudColorHandlerRandom<pcl::PointXYZ> color; viewer.addPointCloud(cloud,color,"color cloud"); // 指定id为"color cloud"点云的属性,点的属性名是PCL_VISUALIZER_POINT_SIZE(直径),值是5 viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE,5,"color cloud"); // 加一个1倍缩放的坐标系 viewer.addCoordinateSystem(1.0); while(!viewer.wasStopped()){ // 每次都刷新一下数据 viewer.spinOnce(); } return 0; }
- 调用
transforms.h
引入仿射变换的头文件,来对点云进行变化处理
#include <thread> #include <pcl/io/io.h> #include <pcl/io/pcd_io.h> #include <pcl/common/transforms.h> #include <pcl/visualization/pcl_visualizer.h> using namespace std; int main(int argc, char **argv) { // 创建pcl指针 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>); // 将点云图加载到指针 pcl::io::loadPCDFile("bunny.pcd", *cloud); pcl::visualization::PCLVisualizer viewer("my_view"); // 普通加载 //viewer.addPointCloud(cloud); // 设置背景 viewer.setBackgroundColor(0.05, 0.05, 0.05, 0); // 添加点云指定颜色 pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> color(cloud, 0, 255, 255); // 多块点云随机定义 颜色pcl::visualization::PointCloudColorHandlerRandom<pcl::PointXYZ> color; viewer.addPointCloud(cloud, color, "color cloud"); // 指定id为"color cloud"点云的属性,点的属性名是PCL_VISUALIZER_POINT_SIZE(直径),值是5 viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 5, "color cloud"); // 仿射变换 // 创建单位矩阵 Eigen::Affine3f tans = Eigen::Affine3f::Identity(); // x轴平移0.3 tans.translation() << 0.3, 0, 0; // 逆时针绕Z轴旋转45度 tans.rotate(Eigen::AngleAxisf(M_PI/4,Eigen::Vector3f::UnitZ())); pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_trans(new pcl::PointCloud<pcl::PointXYZ>); // 参数一源数据,参数儿新的点云地址,参数三仿射矩阵 pcl::transformPointCloud(*cloud,*cloud_trans,tans); // 新建点云,用来区别 pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> color_trans(cloud_trans,255,0,0); viewer.addPointCloud(cloud_trans,color_trans,"translate cloud"); viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE,5,"translate cloud"); while (!viewer.wasStopped()) { // 每次都刷新一下数据 viewer.spinOnce(); } return 0; }
- 点云的生成有很多种,可以用CAD,或是用深度的图像获取物体一个方向的点云,在运行点云程序前,导入点云库我发现了一个问题,当我在CMakeList中
点云数据
-
点云的原数据
- 点云格式如下,首先是指定点云文件的版本,然后FIELDS是点云的维度,多的情况下会有x y z r g b 等等。SIZE表示每个维度的字节大小,TYPE是纬度的类型,COUNT表示纬度的元素个数,ViewPoint是Camera视角,默认0,0,0,1,0,0,0,0。DATA数据方式ascii(可读),binary(不可读)。
# .PCD v.5 - Point Cloud Data file format VERSION .5 FIELDS x y z SIZE 4 4 4 TYPE F F F COUNT 1 1 1 WIDTH 397 HEIGHT 1 POINTS 397 DATA ascii 0.0054216 0.11349 0.040749 -0.0017447 0.11425 0.041273 -0.010661 0.11338 0.040916 0.026422 0.11499 0.032623 0.024545 0.12284 0.024255 ……
- 我们这里读取的数据是序列化后的数据,但是我们要运行某一个数据集,我们可以对数据进行反序列化,或者对数据做一个生成
# include <pcl/io/pcd_io.h> # include <pcl/point_types.h> # include <pcl/visualization/pcl_visualizer.h> using namespace std; int main(int argc,char** argv){ pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>); if(pcl::io::loadPCDFile("bunny.pcd",*cloud)==-1){ PCL_ERROR("could not read bunny.pcd\n"); return -1; } // 获取每个点的数据 for (int i = 0; i < cloud->size(); ++i) { cout<<cloud->points[i].x<<" "<< cloud->points[i].y<<" "<<cloud->points[i].z<<"\n"<<endl; } //创建点云 pcl::PointCloud<pcl::PointXYZ>::Ptr create_cloud; cloud->width=360; cloud->height=1; cloud->is_dense= false; cloud->points.resize(cloud->width*cloud->height); for(int i=0;i<cloud->points.size();i++){ cloud->points[i].x = sin(i)*cos(i*20); cloud->points[i].y = sin(i)*sin(i*20); cloud->points[i].z = cos(i); } pcl::io::savePCDFile("my_one.pcd",*cloud); pcl::io::loadPCDFile("my_one.pcd",*cloud); pcl::visualization::PCLVisualizer viewer("my_one_view"); viewer.addPointCloud(cloud,"temp1"); viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE,5,"temp1"); viewer.spin(); }
- 点云的文件格式有很多,比如PLY,OBJ,STL,OBI,X3D……,这里如果想吧点云文件,转为pcd格式可以用以下命令
pcl_ply2pcd xxx.ply xxx.pcd cl_obj2pcd xxx.ply xxx.pcd ……
点云的基础算法
-
kd tree
-
通过3D相机获取的数据量一般都是很大的,这大量的数据主要是物体表面特征的的结合,这些点基于邻域关系建立快速的比对功能,就需要对这些离散的点进行拓扑关系建立,如此就可以降采样,计算特征向量,点云匹配,点云拆分等功能。
-
k-d tree(k-dimensional tree)是一个数据结构,一个包含特定约束的二叉树,k-d tree对范围搜索和最近邻居搜索非常有用(先在x轴中位找到对应的中值,作为根,然后更具y轴中位的中位作为根,然后z轴中位……,然后不断循环,小于的作为左子树,大于的作为右子树,如此来查询最近的点坐标,从而避免不断迭代计算点的距离)。
-
例如:这里有两个维度分别是XY轴,根据kd-tree为了跟快的找到每个节点我们需要对点进行划分,形成二叉树。比如先从X轴开始以中值点A开始红虚线为第一道,然后区分了两块分别位于左子树和右子树,然后根据y中值B和C进行两块的划分(绿虚线),最后只剩下了EFD三点,再在3点上进行划分(蓝虚线),可以发现没有剩下的点了,划分结束。
- 这下面介绍了两个临近点检测的方法:
// // Created by 零蚀 on 2021/4/18. // #include <pcl/io/pcd_io.h> #include <pcl/io/io.h> #include <pcl/search/kdtree.h> #include <pcl/search/impl/search.hpp> #include <pcl/visualization/pcl_visualizer.h> using namespace std; int main(int argc, char **argv) { pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>()); pcl::io::loadPCDFile("bunny.pcd", *cloud); auto points = cloud->points; // 设置需要搜索的点 pcl::PointXYZ point = points[100]; /** * k 索引的临近点个数 * pointIdSearch 搜索到的临近点的索引 * pointNKNSquareDistance 搜索到的临近点的距离平方 */ int k=10; std::vector<int> pointIdSearch(k); std::vector<float> pointNKNSquareDistance(k); // 定义kd tree pcl::search::KdTree<pcl::PointXYZ> kd_tree; kd_tree.setInputCloud(cloud); // 搜索point的最近的点 int res = kd_tree.nearestKSearch(point, k, pointIdSearch, pointNKNSquareDistance); // 按照半径查找 //int res = kd_tree.radiusSearch(point, 5, pointIdSearch, pointNKNSquareDistance) if (res > 0) { for (int i = 0; i < pointIdSearch.size(); ++i) { std::cout << "距离:" << pointNKNSquareDistance[i] << std::endl; } } pcl::visualization::PCLVisualizer viewer("view"); viewer.addPointCloud(cloud,"cloud"); viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE,5,"cloud"); // 目标点画一个球 viewer.addSphere(point,0.005,"sphere",0); // 目标原点链接直线 pcl::PointXYZ origin = points[0]; viewer.addLine(origin,point); while (!viewer.wasStopped()) { // 每次都刷新一下数据 viewer.spinOnce(); } return 0; }
-
-
octree
- 八叉树主要的思想是讲一个空间根据中点横纵切分八块,以此来不断缩小范围定位到目标,八叉树可以很快的定位到物体在3D空间的位置。octree也可以实现最近的k值领域搜索和半径搜索。工具可见
pcl_octree_viewer /Volumes/zero/resource/bunny.pcd 0.0001
- 这上面有些命令提示,a 缩小立方体,z 放大立方体,b 显示立方体中的提速,v 去除立方体。
- 八叉树的代码
#include <pcl/point_cloud.h> #include <pcl/io/pcd_io.h> #include <pcl/octree/octree_search.h> #include <vector> #include <pcl/visualization/pcl_visualizer.h> int main(int argc,char** argv){ pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>); pcl::io::loadPCDFile("my_one.pcd",*cloud); // 设置分辨率 float resolution = 36.0f; // resolution描述叶子结点最小的体素尺寸 pcl::octree::OctreePointCloudSearch<pcl::PointXYZ> octree(resolution); // 输入点云 octree.setInputCloud(cloud); // 构建八叉树 octree.addPointsFromInputCloud(); // 目标点 pcl::PointXYZ pointSearch = cloud->points[100]; std::vector<int> pointIdx; // 最近邻域搜索 octree.approxNearestSearch() // 半径搜索 octree.radiusSearch() if(octree.voxelSearch(pointSearch,pointIdx)){ for (const auto &item : pointIdx){ std::cout << "x:" << cloud->points[item].x << std::endl; } } return 0; }
- 八叉树主要的思想是讲一个空间根据中点横纵切分八块,以此来不断缩小范围定位到目标,八叉树可以很快的定位到物体在3D空间的位置。octree也可以实现最近的k值领域搜索和半径搜索。工具可见
点云的滤波
-
滤波方法
-
滤波是为了去噪,过滤离群点,可以修复信息损失,孔洞等情况。滤波作为点云预处理重要的一步,pcl提供双边,高斯,条件,直筒,RANSAG(基于随机采样的一致性)滤波等,这参考opencv。
-
直通滤波的代码案例(Pass_through),如图所示我们只保留了z轴的上半轴的球体数据。
/** Mainfest **/ //find_package(PCL REQUIRED COMPONENTS common io visualization filters) 这里可以指定加一些功能模块或者不写全都加载 find_package(PCL REQUIRED COMPONENTS) include_directories(${PCL_INCLUDE_DIRS}) link_directories(${PCL_LIBRARY_DIRS}) add_definitions(${PCL_DEFINITIONS}) add_executable(PCL_pass_through pass_through.cpp) target_link_libraries(PCL_pass_through ${PCL_LIBRARIES}) /** code **/ #include <pcl/point_types.h> #include <pcl/io/pcd_io.h> #include <pcl/filters/passthrough.h> #include <pcl/filters/grid_minimum.h> #include <pcl/visualization/pcl_visualizer.h> int main(int argc,char** argv){ pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>); pcl::PointCloud<pcl::PointXYZ>::Ptr pass_through(new pcl::PointCloud<pcl::PointXYZ>); pcl::io::loadPCDFile("my_one.pcd",*cloud); // 构建滤波对象 pcl::PassThrough<pcl::PointXYZ> pass; pass.setInputCloud(cloud); // 指定过滤方向(直通滤波只能过滤一个方向的数据) pass.setFilterFieldName("z"); // 保留的数据范围 pass.setFilterLimits(0,1); // 开始过滤 pass.filter(*pass_through); // 显示过滤后的样式 pcl::visualization::PCLVisualizer viewer; viewer.addPointCloud(pass_through); while(!viewer.wasStopped()){ viewer.spinOnce(); } return 0; }
-
-
降采样
- 降采样是为了将密集的大数据给降低数据量,一个是我们采集的到数据一般都很多很密集的数据,但是我们在开发过程中,基本很难用到全部数据信息,为了加快运算速率,所以经常会使用到降采样方式。
#include <pcl/io/pcd_io.h> #include <pcl/point_types.h> #include <pcl/visualization/pcl_visualizer.h> #include <pcl/filters/voxel_grid.h> int main(int argc,char **argv){ // PCLPointCloud2是为了简化PointCloud<pcl::PointXYZ>指定类型,有点像auto pcl::PCLPointCloud2::Ptr cloud(new pcl::PCLPointCloud2()); pcl::PCLPointCloud2::Ptr filter(new pcl::PCLPointCloud2()); pcl::io::loadPCDFile("my_one.pcd",*cloud); // 设置树最小节点的体素尺寸大小/叶子节点大小(八叉树点的空间占有大小) float leafSize = 0.01; // 创建对象 pcl::VoxelGrid<pcl::PCLPointCloud2> voxelGrid; voxelGrid.setInputCloud(cloud); // 每个维度都限制体素尺寸 voxelGrid.setLeafSize(leafSize,leafSize,leafSize); // 指定数据的对象 voxelGrid.filter(*filter); // 展示 pcl::visualization::PCLVisualizer viewer("view"); // 将数据保存 pcl::PCDWriter writer; writer.write("downsampling.pcd",*filter); return 0; }
- 显示多个试图
// 设置大小相同的 pcl_viewer -multiview xx.pcd yy.pcd
-
rm离群点(除噪)
-
很多点在数据上是没有意义的点,或者就是噪点,这个一般是有外界环境,硬件采集的问题,导致很多没有意义,影响数据的结果的离群点。稀疏群值的消除基于点到邻居距离的分布计算,对于每个点,我们计算从他到所有邻居的点平均距离,通过假设结果分局具有均值和标准差的高斯分布,可以将其平局距离子啊由金全局距离均值和标准差定义的区间之外的点视为离群点,并对其从数据中抽离。
-
StatisticalOutliterRemoval(统计学离群点移除过滤器)方法除燥。
#include <pcl/io/pcd_io.h> #include <pcl/point_types.h> #include <pcl/visualization/pcl_visualizer.h> #include <pcl/filters/statistical_outlier_removal.h> int main(int argc,char** argv){ pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>()); pcl::PointCloud<pcl::PointXYZ>::Ptr filter(new pcl::PointCloud<pcl::PointXYZ>()); // 读取点云 pcl::PCDReader reader; reader.read<pcl::PointXYZ>("bunny.pcd",*cloud); // 构建过滤对象 pcl::StatisticalOutlierRemoval<pcl::PointXYZ> rm; rm.setInputCloud(cloud); // 设置最近邻居的数量K rm.setMeanK(50); // 设置标准差的阈值,大于这个值被认定为离群点 rm.setStddevMulThresh(3); // rm.setNegative(true); // 结果取反 rm.filter(*filter); pcl::PCDWriter writer; // writer.write("out_rm.pcd",*filter,false); std::cout << cloud->points.size() << std::endl; std::cout << filter->points.size() << std::endl; //显示 pcl::visualization::PCLVisualizer viewer("viewer"); viewer.addPointCloud(filter); while(!viewer.wasStopped()){ viewer.spinOnce(); } return 0; }
- RadiusOutlierRemoval指定半径指定邻居数量才可以保留(半径滤波)
#include <pcl/io/pcd_io.h> #include <pcl/point_types.h> #include <pcl/visualization/pcl_visualizer.h> #include <pcl/filters/radius_outlier_removal.h> int main(int argc,char** argv){ pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>()); pcl::PointCloud<pcl::PointXYZ>::Ptr filter(new pcl::PointCloud<pcl::PointXYZ>()); // 读取点云 pcl::PCDReader reader; reader.read<pcl::PointXYZ>("more_circle.pcd",*cloud); pcl::StatisticalOutlierRemoval<pcl::PointXYZ> rm1; // 半径内指定数量过滤 pcl::RadiusOutlierRemoval<pcl::PointXYZ> rm; rm.setRadiusSearch(0.1); rm.setInputCloud(cloud); // 设置半径内的最近邻居数量 rm.setMinNeighborsInRadius(10); rm.filter(*filter); std::cout << cloud->points.size() << std::endl; // 输出36080 std::cout << filter->points.size() << std::endl;// 输出36015 //显示 pcl::visualization::PCLVisualizer viewer("viewer"); viewer.addPointCloud(filter); while(!viewer.wasStopped()){ viewer.spinOnce(); } return 0; }
- Condition条件滤波
#include <pcl/io/pcd_io.h> #include <pcl/point_types.h> #include <pcl/visualization/pcl_visualizer.h> #include <pcl/filters/conditional_removal.h> int main(int argc,char** argv){ pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>()); pcl::PointCloud<pcl::PointXYZ>::Ptr filter(new pcl::PointCloud<pcl::PointXYZ>()); // 读取点云 pcl::PCDReader reader; reader.read<pcl::PointXYZ>("my_one.pcd",*cloud); // 构建一个与条件(ConditionOr 或条件) pcl::ConditionAnd<pcl::PointXYZ>::Ptr condition(new pcl::ConditionAnd<pcl::PointXYZ>()); // 添加指定条件(z坐标轴,GT 大<GE 大于等于,EQ equal>,0.0条件值) condition->addComparison(pcl::FieldComparison<pcl::PointXYZ>::ConstPtr(new pcl::FieldComparison<pcl::PointXYZ>("z",pcl::ComparisonOps::GT,0.0))); // pcl::ConditionalRemoval<pcl::PointXYZ> condUtil; condUtil.setCondition(condition); condUtil.setInputCloud(cloud); // condUtil.setKeepOrganized(true); //保留过滤的点 condUtil.filter(*filter); std::cout << cloud->points.size() << std::endl; //显示 pcl::visualization::PCLVisualizer viewer("viewer"); viewer.addPointCloud(filter); while(!viewer.wasStopped()){ viewer.spinOnce(); } return 0; }
-
🔗 前言
🔗 机器人视觉篇
🔗 NO.2 降采样&边界&关键点
🔗 NO.3 RANSAC & Feature
🔗 NO.4 点云分割和分割
🔗 NO.5 手眼标定
🔗 NO.6 kinect2获取 & 合成3D点云
🔗 NO.7 位姿 & 捕获