激光雷達作為自動駕駛最常用的傳感器,經常需要使用激光雷達來做建圖、定位和感知等任務。
而這時候使用降低點云規模的預處理方法,可以能夠去除無關區域的點以及降低點云規模。并能夠給后續的PCL點云分割帶來有效的收益。
點云預處理
1.1 指定區域獲取點云
在實際使用中,我們可以看出,雖然點云的分布范圍較廣,但大部分的點都集中的中間區域,距離越遠點云越稀疏,相對的信息量也越小。
此外還能明顯看到一些離群點,因此我們可以篩選掉一些較遠的點,只保留我們感興趣范圍內的點。以下為保留 x 在 30m,y 在 15m,z 在 2m 范圍內的點的效果:
template < class PointType >void removePointsOutsideRegion(boost::shared_ptr< pcl::PointCloud< PointType > >& src_cloud_ptr, boost::shared_ptr< pcl::PointCloud< PointType > >& dst_cloud_ptr, const std::pair< double, double >& x_range, const std::pair< double, double >& y_range, const std::pair< double, double >& z_range) { int num_points = src_cloud_ptr- >points.size(); boost::shared_ptr< pcl::PointCloud< PointType > > cloud_ptr(new pcl::PointCloud< PointType >()); cloud_ptr- >points.reserve(num_points); for (const auto& pt : src_cloud_ptr- >points) { bool inside = (pt.x >= x_range.first && pt.x < = x_range.second && pt.y >= y_range.first && pt.y < = y_range.second && pt.z >= z_range.first && pt.z < = z_range.second); if (inside) { cloud_ptr- >points.push_back(pt); } } dst_cloud_ptr = cloud_ptr;} // 或者使用CropBox來實現去除給定區域外的點 pcl::CropBox< pcl::PointXYZ > box_filter; box_filter.setInputCloud(cloud_ptr); box_filter.setMin(Eigen::Vector4f(keep_x_range.first, keep_y_range.first, keep_z_range.first, 1.0)); box_filter.setMax(Eigen::Vector4f(keep_x_range.second, keep_y_range.second, keep_z_range.second, 1.0)); box_filter.filter(*temp_cloud_ptr);
1.2 去除給定區域的點
在某些情況下,我們也會需要去除給定區域內部的點,比如在自動駕駛中激光掃描的區域有一部分來自搭載激光雷達的車子本身
template < class PointType >void filterPointsWithinRegion(boost::shared_ptr< pcl::PointCloud< PointType > >& src_cloud_ptr, boost::shared_ptr< pcl::PointCloud< PointType > >& dst_cloud_ptr, const std::pair< double, double >& x_range, const std::pair< double, double >& y_range, const std::pair< double, double >& z_range, bool remove) { int num_points = src_cloud_ptr- >points.size(); boost::shared_ptr< pcl::PointCloud< PointType > > cloud_ptr(new pcl::PointCloud< PointType >()); cloud_ptr- >points.reserve(num_points); for (const auto& pt : src_cloud_ptr- >points) { bool inside = (pt.x >= x_range.first && pt.x < = x_range.second && pt.y >= y_range.first && pt.y < = y_range.second && pt.z >= z_range.first && pt.z < = z_range.second); if (inside ^ remove) { cloud_ptr- >points.push_back(pt); } } dst_cloud_ptr = cloud_ptr;}// PassThrough: 可以指定點云中的點的某個字段進行范圍限制,將其設為 true 時可以進行給定只保留給定范圍內的點的功能 pcl::PassThrough< pcl::PointXYZ > pass_filter; bool reverse_limits = true; pass_filter.setInputCloud(filtered_cloud_ptr); pass_filter.setFilterFieldName("x"); pass_filter.setFilterLimits(-5, 5); pass_filter.getFilterLimitsNegative(reverse_limits); // reverse the limits pass_filter.filter(*filtered_cloud_ptr); pass_filter.setFilterFieldName("y"); pass_filter.setFilterLimits(-2, 2); pass_filter.getFilterLimitsNegative(reverse_limits); // reverse the limits pass_filter.filter(*filtered_cloud_ptr); pass_filter.setFilterFieldName("z"); pass_filter.setFilterLimits(-2, 2); pass_filter.getFilterLimitsNegative(reverse_limits); // reverse the limits pass_filter.filter(*filtered_cloud_ptr);
1.3 點云下采樣
1.3.1 柵格化采樣
這里第一點介紹柵格化的下采樣,在 PCL 中對應的函數為體素濾波。柵格化下采樣大致的思路是計算整體點云的中心。
通過計算每個點到中心的距離結合要求的分辨率計算柵格對應的坐標,并入其中,最后遍歷每個包含點的柵格計算其中點的幾何中心或者取該柵格中心加入目標點云即可。
pcl::VoxelGrid< pcl::PointXYZ > voxel_filter; voxel_filter.setLeafSize(0.1, 0.1, 0.1); voxel_filter.setInputCloud(cloud_ptr); voxel_filter.filter(*filtered_cloud_ptr);
1.3.2 點云所在區域密度規律濾波
該方法直接基于點云分布密度進行去噪,直觀的感受是可以根據點云中每個點所在區域判斷其是否是噪聲,一般來說噪聲點所在區域都比較稀疏。
pcl::RadiusOutlierRemoval< pcl::PointXYZ >::Ptr radius_outlier_removal( new pcl::RadiusOutlierRemoval< pcl::PointXYZ >(true)); radius_outlier_removal- >setInputCloud(cloud_ptr); radius_outlier_removal- >setRadiusSearch(1.0); radius_outlier_removal- >setMinNeighborsInRadius(10); radius_outlier_removal- >filter(*filtered_cloud_ptr);
1.3.3 點云所在區域分布規律濾波
除了根據稠密意以外還可以根據距離來篩選濾波,每個點計算其到周圍若干點的平均距離,如果這個平均距離相對于整體點云中所有點的平均距離較近,則認為其不是噪點
// PCL built-in radius removal pcl::StatisticalOutlierRemoval<pcl::PointXYZ>::Ptr statistical_outlier_removal( new pcl::StatisticalOutlierRemoval<pcl::PointXYZ>(true)); // set to true if we want to extract removed indices statistical_outlier_removal->setInputCloud(cloud_ptr); statistical_outlier_removal->setMeanK(20); statistical_outlier_removal->setStddevMulThresh(2.0); statistical_outlier_removal->filter(*filtered_cloud_ptr);
1.3.4 根據點云是否可以被穩定觀察到篩選
LOAM 中對點云中的點是否能形成可靠特征的一個判斷標準是它能否被穩定觀察到。
LOAM 中著重提了這兩種情況的點是不穩定的:
- 特征成平面和掃描線近乎平行
- 特征掃描到的其中一端被另一個平面擋住,這部分的點也不穩定
template < typename PointType >void filter_occuluded_points(boost::s
-
傳感器
+關注
關注
2551文章
51163瀏覽量
754156 -
激光雷達
+關注
關注
968文章
3981瀏覽量
190014 -
自動駕駛
+關注
關注
784文章
13838瀏覽量
166532 -
點云
+關注
關注
0文章
58瀏覽量
3801
發布評論請先 登錄
相關推薦
評論