PCL點雲配準(2)

(1)正態分佈變換進行配準(normal Distributions Transform)ios

介紹關於如何使用正態分佈算法來肯定兩個大型點雲之間的剛體變換,正態分佈變換算法是一個配准算法,它應用於三維點的統計模型,使用標準最優化技術來肯定兩個點雲間的最優匹配,由於其在配準的過程當中不利用對應點的特徵計算和匹配,因此時間比其餘方法比較快,算法

對於代碼的解析微信

/*
使用正態分佈變換進行配準的實驗 。其中room_scan1.pcd  room_scan2.pcd這些點雲包含同一房間360不一樣視角的掃描數據
*/
#include <iostream>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>

#include <pcl/registration/ndt.h>      //NDT(正態分佈)配準類頭文件
#include <pcl/filters/approximate_voxel_grid.h>   //濾波類頭文件  (使用體素網格過濾器處理的效果比較好)

#include <pcl/visualization/pcl_visualizer.h>
#include <boost/thread/thread.hpp>

int
main (int argc, char** argv)
{
  // 加載房間的第一次掃描點雲數據做爲目標
  pcl::PointCloud<pcl::PointXYZ>::Ptr target_cloud (new pcl::PointCloud<pcl::PointXYZ>);
  if (pcl::io::loadPCDFile<pcl::PointXYZ> ("room_scan1.pcd", *target_cloud) == -1)
  {
    PCL_ERROR ("Couldn't read file room_scan1.pcd \n");
    return (-1);
  }
  std::cout << "Loaded " << target_cloud->size () << " data points from room_scan1.pcd" << std::endl;

  // 加載重新視角獲得的第二次掃描點雲數據做爲源點雲
  pcl::PointCloud<pcl::PointXYZ>::Ptr input_cloud (new pcl::PointCloud<pcl::PointXYZ>);
  if (pcl::io::loadPCDFile<pcl::PointXYZ> ("room_scan2.pcd", *input_cloud) == -1)
  {
    PCL_ERROR ("Couldn't read file room_scan2.pcd \n");
    return (-1);
  }
  std::cout << "Loaded " << input_cloud->size () << " data points from room_scan2.pcd" << std::endl;
  //以上的代碼加載了兩個PCD文件獲得共享指針,後續配準是完成對源點雲到目標點雲的參考座標系的變換矩陣的估計,獲得第二組點雲變換到第一組點雲座標系下的變換矩陣
  // 將輸入的掃描點雲數據過濾到原始尺寸的10%以提升匹配的速度,只對源點雲進行濾波,減小其數據量,而目標點雲不須要濾波處理
  //由於在NDT算法中在目標點雲對應的體素網格數據結構的統計計算不使用單個點,而是使用包含在每一個體素單元格中的點的統計數據
  pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_cloud (new pcl::PointCloud<pcl::PointXYZ>);
  pcl::ApproximateVoxelGrid<pcl::PointXYZ> approximate_voxel_filter;
  approximate_voxel_filter.setLeafSize (0.2, 0.2, 0.2);
  approximate_voxel_filter.setInputCloud (input_cloud);
  approximate_voxel_filter.filter (*filtered_cloud);
  std::cout << "Filtered cloud contains " << filtered_cloud->size ()
            << " data points from room_scan2.pcd" << std::endl;

  // 初始化正態分佈(NDT)對象
  pcl::NormalDistributionsTransform<pcl::PointXYZ, pcl::PointXYZ> ndt;

  // 根據輸入數據的尺度設置NDT相關參數

  ndt.setTransformationEpsilon (0.01);   //爲終止條件設置最小轉換差別
  
  ndt.setStepSize (0.1);    //爲more-thuente線搜索設置最大步長

  ndt.setResolution (1.0);   //設置NDT網格網格結構的分辨率(voxelgridcovariance)
  //以上參數在使用房間尺寸比例下運算比較好,可是若是須要處理例如一個咖啡杯子的掃描之類更小的物體,須要對參數進行很大程度的縮小

  //設置匹配迭代的最大次數,這個參數控制程序運行的最大迭代次數,通常來講這個限制值以前優化程序會在epsilon變換閥值下終止
  //添加最大迭代次數限制可以增長程序的魯棒性阻止了它在錯誤的方向上運行時間過長
  ndt.setMaximumIterations (35);

  ndt.setInputSource (filtered_cloud);  //源點雲
  // Setting point cloud to be aligned to.
  ndt.setInputTarget (target_cloud);  //目標點雲

  // 設置使用機器人測距法獲得的粗略初始變換矩陣結果
  Eigen::AngleAxisf init_rotation (0.6931, Eigen::Vector3f::UnitZ ());
  Eigen::Translation3f init_translation (1.79387, 0.720047, 0);
  Eigen::Matrix4f init_guess = (init_translation * init_rotation).matrix ();

  // 計算須要的剛體變換以便將輸入的源點雲匹配到目標點雲
  pcl::PointCloud<pcl::PointXYZ>::Ptr output_cloud (new pcl::PointCloud<pcl::PointXYZ>);
  ndt.align (*output_cloud, init_guess);
   //這個地方的output_cloud不能做爲最終的源點雲變換,由於上面對點雲進行了濾波處理
  std::cout << "Normal Distributions Transform has converged:" << ndt.hasConverged ()
            << " score: " << ndt.getFitnessScore () << std::endl;

  // 使用建立的變換對爲過濾的輸入點雲進行變換
  pcl::transformPointCloud (*input_cloud, *output_cloud, ndt.getFinalTransformation ());

  // 保存轉換後的源點雲做爲最終的變換輸出
  pcl::io::savePCDFileASCII ("room_scan2_transformed.pcd", *output_cloud);

  // 初始化點雲可視化對象
  boost::shared_ptr<pcl::visualization::PCLVisualizer>
  viewer_final (new pcl::visualization::PCLVisualizer ("3D Viewer"));
  viewer_final->setBackgroundColor (0, 0, 0);  //設置背景顏色爲黑色
 
  // 對目標點雲着色可視化 (red).
  pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>
  target_color (target_cloud, 255, 0, 0);
  viewer_final->addPointCloud<pcl::PointXYZ> (target_cloud, target_color, "target cloud");
  viewer_final->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE,
                                                  1, "target cloud");

  // 對轉換後的源點雲着色 (green)可視化.
  pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>
  output_color (output_cloud, 0, 255, 0);
  viewer_final->addPointCloud<pcl::PointXYZ> (output_cloud, output_color, "output cloud");
  viewer_final->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE,
                                                  1, "output cloud");

  // 啓動可視化
  viewer_final->addCoordinateSystem (1.0);  //顯示XYZ指示軸
  viewer_final->initCameraParameters ();   //初始化攝像頭參數

  // 等待直到可視化窗口關閉
  while (!viewer_final->wasStopped ())
  {
    viewer_final->spinOnce (100);
    boost::this_thread::sleep (boost::posix_time::microseconds (100000));
  }

  return (0);
}

編譯完成運行的結果:數據結構

(2)本實驗將學習如何編寫一個交互式ICP可視化的程序。該程序將加載點雲並對其進行剛性變換。以後,使用ICP算法將變換後的點雲與原來的點雲對齊。每次用戶按下「空格」,進行ICP迭代,刷新可視化界面。app

在這裏原始例程使用的是PLY格式的文件,能夠找一個PLY格式的文件進行實驗,也可使用格式轉換文件 把PCD 文件轉爲PLY文件ide

#include <iostream>
#include <string>

#include <pcl/io/ply_io.h>    //PLY相關頭文件
#include <pcl/point_types.h>  //
#include <pcl/registration/icp.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <pcl/console/time.h>   

typedef pcl::PointXYZ PointT;
typedef pcl::PointCloud<PointT> PointCloudT;   //定義點雲的格式

bool next_iteration = false;     

void
print4x4Matrix (const Eigen::Matrix4d & matrix)    //打印旋轉矩陣和平移矩陣
{
  printf ("Rotation matrix :\n");
  printf ("    | %6.3f %6.3f %6.3f | \n", matrix (0, 0), matrix (0, 1), matrix (0, 2));
  printf ("R = | %6.3f %6.3f %6.3f | \n", matrix (1, 0), matrix (1, 1), matrix (1, 2));
  printf ("    | %6.3f %6.3f %6.3f | \n", matrix (2, 0), matrix (2, 1), matrix (2, 2));
  printf ("Translation vector :\n");
  printf ("t = < %6.3f, %6.3f, %6.3f >\n\n", matrix (0, 3), matrix (1, 3), matrix (2, 3));
}

void
keyboardEventOccurred (const pcl::visualization::KeyboardEvent& event,
                       void* nothing)
{  //使用空格鍵來增長迭代次數,並更新顯示
  if (event.getKeySym () == "space" && event.keyDown ())
    next_iteration = true;
}

int
main (int argc,
      char* argv[])
{
  // 申明點雲將要使用的
  PointCloudT::Ptr cloud_in (new PointCloudT);  // 原始點雲
  PointCloudT::Ptr cloud_tr (new PointCloudT);  // 轉換後的點雲
  PointCloudT::Ptr cloud_icp (new PointCloudT);  // ICP 輸出點雲

  // 檢查程序輸入命令的合法性  
  if (argc < 2)  //若是隻有一個命令說明沒有指定目標點雲,因此會提示用法
  {
    printf ("Usage :\n");
    printf ("\t\t%s file.ply number_of_ICP_iterations\n", argv[0]);
    PCL_ERROR ("Provide one ply file.\n");
    return (-1);
  }

  int iterations = 1;  // 默認的ICP迭代次數
  if (argc > 2)   
  {
   //若是命令的有兩個以上。說明用戶是將迭代次數做爲傳遞參數
    iterations = atoi (argv[2]);  //傳遞參數的格式轉化爲int型
    if (iterations < 1)  //同時不能設置迭代次數爲1
    {
      PCL_ERROR ("Number of initial iterations must be >= 1\n");
      return (-1);
    }
  }

  pcl::console::TicToc time;     //申明時間記錄
  time.tic ();       //time.tic開始  time.toc結束時間
  if (pcl::io::loadPLYFile (argv[1], *cloud_in) < 0)
  {
    PCL_ERROR ("Error loading cloud %s.\n", argv[1]);
    return (-1);
  }
  std::cout << "\nLoaded file " << argv[1] << " (" << cloud_in->size () << " points) in " << time.toc () << " ms\n" << std::endl;

  //定義旋轉矩陣和平移向量Matrix4d是爲4*4的矩陣
  Eigen::Matrix4d transformation_matrix = Eigen::Matrix4d::Identity ();  //初始化

  // 旋轉矩陣的定義能夠參考 ( https://en.wikipedia.org/wiki/Rotation_matrix)
  double theta = M_PI / 8;  // 旋轉的角度用弧度的表示方法
  transformation_matrix (0, 0) = cos (theta);
  transformation_matrix (0, 1) = -sin (theta);
  transformation_matrix (1, 0) = sin (theta);
  transformation_matrix (1, 1) = cos (theta);

  // Z軸的平移向量 (0.4 meters)
  transformation_matrix (2, 3) = 0.4;

  //打印轉換矩陣
  std::cout << "Applying this rigid transformation to: cloud_in -> cloud_icp" << std::endl;
  print4x4Matrix (transformation_matrix);

  // 執行點雲轉換
  pcl::transformPointCloud (*cloud_in, *cloud_icp, transformation_matrix);
  *cloud_tr = *cloud_icp;  // 備份cloud_icp賦值給cloud_tr爲後期使用

  // 迭代最近點算法
  time.tic ();        //時間
  pcl::IterativeClosestPoint<PointT, PointT> icp;
  icp.setMaximumIterations (iterations);    //設置最大迭代次數iterations=true
  icp.setInputSource (cloud_icp);   //設置輸入的點雲
  icp.setInputTarget (cloud_in);    //目標點雲
  icp.align (*cloud_icp);          //匹配後源點雲
  icp.setMaximumIterations (1);  // 設置爲1以便下次調用
  std::cout << "Applied " << iterations << " ICP iteration(s) in " << time.toc () << " ms" << std::endl;

  if (icp.hasConverged ())//icp.hasConverged ()=1(true)輸出變換矩陣的適合性評估
  {
    std::cout << "\nICP has converged, score is " << icp.getFitnessScore () << std::endl;
    std::cout << "\nICP transformation " << iterations << " : cloud_icp -> cloud_in" << std::endl;
    transformation_matrix = icp.getFinalTransformation ().cast<double>();
    print4x4Matrix (transformation_matrix);
  }
  else
  {
    PCL_ERROR ("\nICP has not converged.\n");
    return (-1);
  }

  // 可視化ICP的過程與結果
  pcl::visualization::PCLVisualizer viewer ("ICP demo");
  // 建立兩個觀察視點
  int v1 (0);
  int v2 (1);
  viewer.createViewPort (0.0, 0.0, 0.5, 1.0, v1);
  viewer.createViewPort (0.5, 0.0, 1.0, 1.0, v2);

  // 定義顯示的顏色信息
  float bckgr_gray_level = 0.0;  // Black
  float txt_gray_lvl = 1.0 - bckgr_gray_level;

  // 原始的點雲設置爲白色的
  pcl::visualization::PointCloudColorHandlerCustom<PointT> cloud_in_color_h (cloud_in, (int) 255 * txt_gray_lvl, (int) 255 * txt_gray_lvl,
                                                                             (int) 255 * txt_gray_lvl);
  viewer.addPointCloud (cloud_in, cloud_in_color_h, "cloud_in_v1", v1);//設置原始的點雲都是顯示爲白色
  viewer.addPointCloud (cloud_in, cloud_in_color_h, "cloud_in_v2", v2);

  // 轉換後的點雲顯示爲綠色
  pcl::visualization::PointCloudColorHandlerCustom<PointT> cloud_tr_color_h (cloud_tr, 20, 180, 20);
  viewer.addPointCloud (cloud_tr, cloud_tr_color_h, "cloud_tr_v1", v1);

  // ICP配準後的點云爲紅色
  pcl::visualization::PointCloudColorHandlerCustom<PointT> cloud_icp_color_h (cloud_icp, 180, 20, 20);
  viewer.addPointCloud (cloud_icp, cloud_icp_color_h, "cloud_icp_v2", v2);

  // 加入文本的描述在各自的視口界面
 //在指定視口viewport=v1添加字符串「white 。。。」其中"icp_info_1"是添加字符串的ID標誌,(10,15)爲座標16爲字符大小 後面分別是RGB值
  viewer.addText ("White: Original point cloud\nGreen: Matrix transformed point cloud", 10, 15, 16, txt_gray_lvl, txt_gray_lvl, txt_gray_lvl, "icp_info_1", v1);
  viewer.addText ("White: Original point cloud\nRed: ICP aligned point cloud", 10, 15, 16, txt_gray_lvl, txt_gray_lvl, txt_gray_lvl, "icp_info_2", v2);

  std::stringstream ss;
  ss << iterations;            //輸入的迭代的次數
  std::string iterations_cnt = "ICP iterations = " + ss.str ();
  viewer.addText (iterations_cnt, 10, 60, 16, txt_gray_lvl, txt_gray_lvl, txt_gray_lvl, "iterations_cnt", v2);

  // 設置背景顏色
  viewer.setBackgroundColor (bckgr_gray_level, bckgr_gray_level, bckgr_gray_level, v1);
  viewer.setBackgroundColor (bckgr_gray_level, bckgr_gray_level, bckgr_gray_level, v2);

  // 設置相機的座標和方向
  viewer.setCameraPosition (-3.68332, 2.94092, 5.71266, 0.289847, 0.921947, -0.256907, 0);
  viewer.setSize (1280, 1024);  // 可視化窗口的大小

  // 註冊按鍵回調函數
  viewer.registerKeyboardCallback (&keyboardEventOccurred, (void*) NULL);

  // 顯示
  while (!viewer.wasStopped ())
  {
    viewer.spinOnce ();

    //按下空格鍵的函數
    if (next_iteration)
    {
      // 最近點迭代算法
      time.tic ();
      icp.align (*cloud_icp);
      std::cout << "Applied 1 ICP iteration in " << time.toc () << " ms" << std::endl;

      if (icp.hasConverged ())
      {
        printf ("\033[11A");  // Go up 11 lines in terminal output.
        printf ("\nICP has converged, score is %+.0e\n", icp.getFitnessScore ());
        std::cout << "\nICP transformation " << ++iterations << " : cloud_icp -> cloud_in" << std::endl;
        transformation_matrix *= icp.getFinalTransformation ().cast<double>();  // WARNING /!\ This is not accurate!
        print4x4Matrix (transformation_matrix);  // 打印矩陣變換

        ss.str ("");
        ss << iterations;
        std::string iterations_cnt = "ICP iterations = " + ss.str ();
        viewer.updateText (iterations_cnt, 10, 60, 16, txt_gray_lvl, txt_gray_lvl, txt_gray_lvl, "iterations_cnt");
        viewer.updatePointCloud (cloud_icp, cloud_icp_color_h, "cloud_icp_v2");
      }
      else
      {
        PCL_ERROR ("\nICP has not converged.\n");
        return (-1);
      }
    }
    next_iteration = false;
  }
  return (0);
}

生成可執行文件後結果函數

                                       窗口輸出的基本信息學習

                                                    剛開始迭代第一次的結果優化

                                                               按空格鍵不斷迭代的結果this

完畢,若有錯誤請與我聯繫交流,謝謝,大牛請忽略

 

微信公衆號號可掃描二維碼一塊兒共同窗習交流

相關文章
相關標籤/搜索