ICP可以说是最经典的方法之一了,这些天看论文下来很多方法后都要接一下ICP才能有一个比较好看的结果,故而来梳理下ICP的原理以及再看看基于PCL的ICP代码。
ICP在上个世纪[1]就被提出了,历久弥新2333,通过不断迭代使得两个点云进行配准。
=========
优化目标=============
三维空间中两个3D点,
,他们的欧式距离表示为:
三维点云匹配问题的目的是找到P和Q变化的矩阵R和T,对于
,
,利用最小二乘法求解最优解使:
最小时的R和T。
==========步骤=========
========================
效果图:(2ms迭代一次)小角度配准效果尚可,大角度(比如90°就GG了)
环境配置: 地址
#include <iostream> #include <string> #include <pcl/io/ply_io.h> #include <pcl/point_types.h> #include <pcl/registration/icp.h> #include <pcl/visualization/pcl_visualizer.h> #include <pcl/console/time.h> // TicToc 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() { // 声明需要用到的点云(读入的,转换的,ICP调整的三个点云) PointCloudT::Ptr cloud_in(new PointCloudT); // Original point cloud PointCloudT::Ptr cloud_tr(new PointCloudT); // Transformed point cloud PointCloudT::Ptr cloud_icp(new PointCloudT); // ICP output point cloud int iterations = 0; // Default number of ICP iterations pcl::console::TicToc time; time.tic(); std::string filename = "cow-2.ply"; if (pcl::io::loadPLYFile(filename, *cloud_in) < 0) { PCL_ERROR("Error loading cloud %s.\n", filename); system("pause"); return (-1); } std::cout << "\nLoaded file " << filename << " (" << cloud_in->size() << " points) in " << time.toc() << " ms\n" << std::endl; // 定义旋转平移的转换矩阵 Eigen::Matrix4d transformation_matrix = Eigen::Matrix4d::Identity(); // A rotation matrix (see https://en.wikipedia.org/wiki/Rotation_matrix) double theta = M_PI/4 ; // The angle of rotation in radians 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米 // A translation on Z axis (0.4 meters) transformation_matrix(2, 3) = 0.4; //打印出旋转矩阵R和平移T 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; // We backup cloud_icp into cloud_tr for later use // The Iterative Closest Point algorithm time.tic(); pcl::IterativeClosestPoint<PointT, PointT> icp; icp.setMaximumIterations(iterations); icp.setInputSource(cloud_icp); icp.setInputTarget(cloud_in); icp.align(*cloud_icp); icp.setMaximumIterations(1); // We set this variable to 1 for the next time we will call .align () function std::cout << "Applied " << iterations << " ICP iteration(s) in " << time.toc() << " ms" << std::endl; if (icp.hasConverged()) { 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"); system("pause"); return (-1); } // Visualization pcl::visualization::PCLVisualizer viewer("ICP demo"); // Create two vertically separated viewports 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); // The color we will be using float bckgr_gray_level = 0.0; // Black float txt_gray_lvl = 1.0 - bckgr_gray_level; // Original point cloud is white 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); // Transformed point cloud is green 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 aligned point cloud is red 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); // Adding text descriptions in each viewport 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); // Set background color viewer.setBackgroundColor(bckgr_gray_level, bckgr_gray_level, bckgr_gray_level, v1); viewer.setBackgroundColor(bckgr_gray_level, bckgr_gray_level, bckgr_gray_level, v2); // Set camera position and orientation viewer.setCameraPosition(-3.68332, 2.94092, 5.71266, 0.289847, 0.921947, -0.256907, 0); viewer.setSize(1280, 1024); // Visualiser window size // Register keyboard callback : viewer.registerKeyboardCallback(&keyboardEventOccurred, (void*)NULL); // Display the visualiser while (!viewer.wasStopped()) { viewer.spinOnce(); // The user pressed "space" : if (next_iteration) { // The Iterative Closest Point algorithm 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! For "educational" purpose only! print4x4Matrix(transformation_matrix); // Print the transformation between original pose and current pose 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"); system("pause"); return (-1); } } next_iteration = false; } system("pause"); return (0); }
Reference
[1]Zhang Z. Iterative point matching for registration of free-form curves and surfaces[J]. International Journal of Computer Vision, 1994, 13(2):119-152.
[2] ICP相关
[3] ICP参考2
[4] ICP参考3
[5] ICP参考4