PCL點雲(地面點雲)分割:Progressive Morphological Filter

背景:

pcl官方教程:

http://www.pointclouds.org/documentation/tutorials/progressive_morphological_filtering.php#progressive-morphological-filtering

論文:http://users.cis.fiu.edu/~chens/PDF/TGRS.pdf


注:

這個算法本身用於處理高空獲取的激光雷達數據,把地面與非地面的物體分割,來獲取地貌3d地圖的。我跑到數據與這類數據有一個明顯的區別,就是x,y的範圍與z的範圍相差不多,而他們的高空數據,z的變化範圍相比其他兩個軸較小。但是我同樣想試試它是否能幫我魯棒地去除地面的點來達到分割物體和地面的效果。

還有,因爲我的數據本來z軸不是對應着向上的方向,我還旋轉點雲來調整了一下。


1.使用感受

參數多,不看論文細節,無法調參數。如果參數不調好,算法耗時很長。對使用者極度不友好。


2.算法細節(從代碼和論文裏理解的)

首先根據數據裏x, y的範圍值,2d柵格化點雲所佔的空間。每個格子擁有0個或多個點,只是他們的高度(論文裏的evaluation)不同。那麼對於這個格子,如果0個點,用插值找一個點;如果多個點,把最低的點留下來。所以說,現在,每個格子都擁有一個格子內最低點(這裏用lpt(lowest point)替代)。然後,

遍歷每一行()

       遍歷每一個格子()

              做一個“開”運算。開運算需要兩個輸入: 窗口大小(=窗口包括了四周哪幾個的格子),以及窗口內lpt的高度合集。

              那麼開運算是什麼呢,後面會解釋。

              把開運算的結果設置爲以這一個格子爲中心的“窗口內最低點”的高度值。

              如果當前格子的lpt 高於這個“窗口內最低點”到一定程度(高度差距閾值), 這個格子原本包含的所有點(包括lpt)都

             是非地面點,而這個"窗口內最低點"替代這個格子的lpt成爲新的lpt。(你可以理解爲,我先四周找找附近地區的窪點,如果我現在站的位置比這個窪點高了半層樓那麼高,那麼我這個地方不算是地面,那個窪點替代我的位置成爲地面應該所在的位置。否則,我現在這個位置算是地面點)。

      end

end

爲了使算法裏的“窗口內最低點”參考更大範圍的局部點雲(也就是我四周看的時候看更遠一點),算法每運行完上面那個循環,就增大窗口大小和高度閾值一點,然後再運行循環。只要有一個循環裏,一個格子的所有點被視爲非地面點,那麼這些點以後都是非地面點,以後的循環也不用遍歷這個格子了。遍歷若干次後,有些格子的lpt被窗口內最低點替代成爲新的lpt了,有些沒有,但它們現在都有它自己的lpt。最後的這些lpt合集就是地面點雲。

2.1 開運算(谷歌上找資料自己理解的)

那麼,開運算是什麼鬼?其實很簡單,它先對一整行每一個格子做了一個Erosion操作,用一整行Erosion結果再對做一個Dilation操作,用兩幅圖說明你就明白。注意,這裏的窗口用了一維來方便表示,實際是二維窗口。

等於說,我按順序地站在每個格子上,四周找找附近最低的位置,如果這個位置就在我腳下,那我什麼都不做;如果不是在我腳下,那我所站的位置變成和這個最低的位置一樣高度。這是Erosion運算或者說腐蝕運算。

然後在腐蝕運算結果上做反向操作,Dilation稀釋運算。我按順序地站在每個格子上,四周找找附近最高的位置,如果這個位置就在我腳下,那我什麼都不做;如果不是在我腳下,那我所站的位置變成和這個最高的位置一樣高度。

腐蝕運算好理解,但爲什麼要做稀釋運算,我也不知道。歡迎大家給出意見。


3. 調參

因爲不明的原因,算法在我數據上運行時間是半個小時。所以調參研究時間太長,這裏不研究。當時爲了我本人調參,我把ProgressiveMorphologicalFiltering.cpp的內容抽出來,寫成my_pmf這個函數,方便我打印過程的數據。詳見底部的代碼。my_pmf只需要輸入點雲,參數都是放在代碼上方,都是全局變量。最後生成object.pcd和ground.pcd, 你可以通過運行$ ./pcl_viewer object.pcd ground.pcd。pcl_viewer可執行文件一般被放在了linux系統的usr/bin。

調參也可以參考:

https://github.com/PointCloudLibrary/pcl/blob/master/segmentation/include/pcl/segmentation/progressive_morphological_filter.h


4.跑自己的數據集

原點雲

地面點雲:

物體點雲:


分割效果還是很好的,就是運行時間長。


5. 總結

很多參數要設置,而且很難設置,參數需要對算法深度理解才能調好。運行時間長,實時性低(即使跑官方的代碼和數據集,時間也較長)。算法對地面的分割效果好。


6. 代碼

#include <iostream>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl/filters/extract_indices.h>
#include <pcl/segmentation/progressive_morphological_filter.h>

#include <pcl/filters/morphological_filter.h>
#include <pcl/pcl_base.h>
using namespace std;

#define max_window_size 0.05
#define slope 0.7f
#define max_distance 0.1f
#define initial_distance 0.01f
#define cell_size 0.01f
#define base 2.0f
#define exponential true

pcl::PointCloud<pcl::PointXYZ>::Ptr my_pmf (pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in)
{
  // Compute the series of window sizes and height thresholds
  std::vector<float> height_thresholds;
  std::vector<float> window_sizes;
  std::vector<int> ground_indices;
  int iteration = 0;
  float window_size = 0.0f;
  float height_threshold = 0.0f;

  while (window_size < max_window_size)
  {
    // Determine the initial window size.
    if (exponential)
      window_size = cell_size * (2.0f * std::pow (base, iteration) + 1.0f);
    else
      window_size = cell_size * (2.0f * (iteration+1) * base + 1.0f);
    cout << "window_size  " << window_size  << endl;
    // Calculate the height threshold to be used in the next iteration.
    if (iteration == 0)
      height_threshold = initial_distance;
    else
      height_threshold = slope * (window_size - window_sizes[iteration-1]) * cell_size + initial_distance;
    cout << "height_threshold  " << height_threshold  << endl;


    // Enforce max distance on height threshold
    if (height_threshold > max_distance)
      height_threshold = max_distance;

    window_sizes.push_back (window_size);
    height_thresholds.push_back (height_threshold);

    iteration++;
  }

  // Ground indices are initially limited to those points in the input cloud we
  // wish to process
  for (int i=0;i<cloud_in->points.size();i++){
      ground_indices.push_back(i);
  }

  // Progressively filter ground returns using morphological open
  for (size_t i = 0; i < window_sizes.size (); ++i)
  {
    cout<< "Iteration " << i << "height threshold = " << height_thresholds[i] << " window size = " <<
              window_sizes[i] << endl;

    // Limit filtering to those points currently considered ground returns
    typename pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
    pcl::copyPointCloud<pcl::PointXYZ> (*cloud_in, ground_indices, *cloud);

    // Create new cloud to hold the filtered results. Apply the morphological
    // opening operation at the current window size.
    typename pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_f (new pcl::PointCloud<pcl::PointXYZ>);
    pcl::applyMorphologicalOperator<pcl::PointXYZ> (cloud, window_sizes[i], pcl::MORPH_OPEN, *cloud_f);

    // Find indices of the points whose difference between the source and
    // filtered point clouds is less than the current height threshold.
    std::vector<int> pt_indices;
    //cout << "ground.size() = " << ground.size() << endl;
    for (size_t p_idx = 0; p_idx < ground_indices.size (); ++p_idx)
    {
      float diff = cloud->points[p_idx].z - cloud_f->points[p_idx].z;
      //cout << "diff " << diff << endl;
      if (diff < height_thresholds[i])
        pt_indices.push_back (ground_indices[p_idx]);
    }

    // Ground is now limited to pt_indices
    ground_indices.swap (pt_indices);
    cout << "ground now has " << ground_indices.size () << " points" << endl;
  }
  typename pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_out (new pcl::PointCloud<pcl::PointXYZ>);
  // Extract cloud_in with ground indices
  pcl::copyPointCloud<pcl::PointXYZ> (*cloud_in, ground_indices, *cloud_out);
  return cloud_out;
}


int main (int argc, char** argv)
{
    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered (new pcl::PointCloud<pcl::PointXYZ>);
    pcl::PointIndicesPtr ground (new pcl::PointIndices);

    // Fill in the cloud data
    pcl::PCDReader reader;
    // Replace the path below with the path where you saved your file
    reader.read<pcl::PointXYZ> ("test_pcd_from_topview.pcd", *cloud);

    std::cerr << "Cloud before filtering: " << std::endl;
    std::cerr << *cloud << std::endl;

    // Run progressive morphological filter
    cloud_filtered = my_pmf(cloud);

    std::cerr << "Ground cloud after filtering: " << std::endl;
    std::cerr << *cloud_filtered << std::endl;

    pcl::PCDWriter writer;
    writer.write<pcl::PointXYZ> ("ground.pcd", *cloud_filtered, false);

    // Extract non-ground returns
    pcl::ExtractIndices<pcl::PointXYZ> extract;
    extract.setInputCloud (cloud);
    extract.setIndices (ground);
    //extract.filter (*cloud_filtered);
    extract.setNegative (true);
    extract.filter (*cloud_filtered);

    std::cerr << "Object cloud after filtering: " << std::endl;
    std::cerr << *cloud_filtered << std::endl;

    writer.write<pcl::PointXYZ> ("object.pcd", *cloud_filtered, false);

    return (0);
}


發表評論
所有評論
還沒有人評論,想成為第一個評論的人麼? 請在上方評論欄輸入並且點擊發布.
相關文章