為了在每幀點雲中濾除噪聲點,選擇了半徑濾波器,也用高斯濾波器測試過,但是沒有半徑效果好,這裡記錄下在 octomap_server 中增加半徑濾波器的步驟,並在 launch 中配置濾波器引數。
一、半徑濾波器基本原理
放一張彙報用的 PPT 截圖:
原理很簡單就是判斷一個點雲周圍(半徑 R)有沒有足夠多(K)的鄰居點,如果沒有就刪除這個點,否則就保留。
二、基本用法
我一般學習技術喜歡到官網看最原始的教程:Removing outliers using a Conditional or RadiusOutlier removal,這個教程介紹了半徑濾波器(我不清楚中文名到底叫什麼濾波器)的基本用法:
#include <pcl/point_types.h>
#include <pcl/filters/radius_outlier_removal.h>
// 輸入待濾波的原始點雲指標
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
// 儲存濾波後的點雲指標
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered (new pcl::PointCloud<pcl::PointXYZ>);
// 建立濾波器物件
pcl::RadiusOutlierRemoval<pcl::PointXYZ> outrem;
// 設定要濾波的點雲
outrem.setInputCloud(cloud);
// 設定濾波半徑
outrem.setRadiusSearch(0.8);
// 設定濾波最少近鄰數
outrem.setMinNeighborsInRadius (2);
// 執行半徑濾波
outrem.filter (*cloud_filtered);
如果第一次使用 PCL 的濾波器,可以把這個教程自己執行一遍,我之前執行過了,這次就不貼程式碼了,下面分享下我在實際專案中如果使用這個半徑濾波器對我的 octomap_server 構建的八叉樹地圖進行濾波。
三、給我的地圖濾波
3.1 定義半徑濾波器引數
半徑濾波器有 2 個引數:濾波半徑和半徑內部鄰居數,注意資料型別
// 濾波半徑
double m_outrem_radius;
// 半徑內的鄰居數
int m_outrem_neighbors;
在建構函式初始化列表中初始化:
OctomapServer::OctomapServer(const ros::NodeHandle private_nh_, const ros::NodeHandle &nh_)
: ...,
m_outrem_radius(-std::numeric_limits<double>::max()),
m_outrem_neighbors(-std::numeric_limits<int>::max()),
...
從 launch 中讀取啟動引數:
// add outrem filter
m_nh_private.param("outrem_radius", m_outrem_radius, m_outrem_radius);
m_nh_private.param("outrem_neighbors", m_outrem_neighbors, m_outrem_neighbors);
3.2 執行半徑濾波
在 InsertPointCloudCallBack 函式的 PassThough 前執行半徑濾波,即對每一幀點雲在構建八叉樹地圖前進行濾波,主要是為了去掉單獨的離群點:
// 對一幀 pc 點雲進行半徑濾波
pcl::RadiusOutlierRemoval<pcl::PointXYZRGB> outrem;
// 這裡需要傳遞指標,因為我的 pc 不是指標,所以這裡做了 makeShared
outrem.setInputCloud(pc.makeShared());
// 設定濾波半徑,這裡設定為 1m
outrem.setRadiusSearch(m_outrem_radius);
// 設定濾波近鄰數,這裡設定為 10 個
outrem.setMinNeighborsInRadius (m_outrem_neighbors);
// 執行濾波
outrem.filter(pc);
3.3 在 launch 中配置半徑濾波器引數
<param name = "outrem_radius" type = "double" value = "1.0">
<param name = "outrem_neighbors" type = "int" value = "10">
這樣以後就可以從 launch 中直接配置濾波器的引數了,不用每次修改再重新編譯,這樣除錯起來非常方便。
3.4 濾波結果
這是原始地圖,15cm 解析度,紅框內部有很多單個的點:
這是濾波後的效果,濾波半徑 1m,近鄰點 10 個:
效果還是可以的,希望能對你有幫助,如果使用其他的濾波器,按照官方的教程來就行了,掌握學習方法才是最重要的:)