文章目錄
- 引言
- 外參標定原理
- ICP匹配示例
- 參考文獻
引言
多激光雷達系統通常用于自動駕駛或機器人,每個雷達的位置和姿態不同,需要將它們的數據統一到同一個坐標系下。多激光雷達外參標定的核心目標是通過計算不同雷達坐標系之間的剛性變換關系(旋轉矩陣 R R R 和平移向量 t t t),將多個雷達的點云數據統一到同一坐標系下。具體需求包括:
- 數據融合:消除多雷達間的位姿差異,生成全局一致的點云。
- 減少累積誤差:避免多傳感器數據因坐標系不統一導致的定位與建圖誤差。
- 提升感知精度:為自動駕駛或機器人提供更可靠的環境感知能力。
外參標定原理
外參標定本質是求解兩個坐標系之間的最優變換參數,設雷達A的坐標系為源坐標系,雷達B為目標坐標系。對于同一物理點 P P P,其在兩個坐標系下的坐標分別為 P A P_A PA? 和 P B P_B PB?,滿足:
P B = R ? P A + t P_B = R \cdot P_A + t PB?=R?PA?+t
其中 R ∈ S O ( 3 ) R \in SO(3) R∈SO(3) 為旋轉矩陣, t ∈ R 3 t \in \mathbb{R}^3 t∈R3 為平移向量。
一般來說,多激光雷達的主流的外參標定方法有手動標定調參法、自動標定法、基于車輛運動軌跡的標定法。
- 手動標定法:
使用已知幾何形狀的標定物(如立方體、棋盤格),通過人工測量或標定物特征點計算外參。優點:精度高,適合實驗室環境。 缺點:依賴標定物,效率低。
基本步驟是:- 將標定物放置在雷達共同視場內;
- 提取標定物的角點或平面;
- 基于最小二乘法求解 R R R 和 t t t;
- 自動標定法:
基本方式是利用環境中的穩定特征(如地面、建筑物邊緣)自動對齊點云,優點在于無需標定物、適應性較強,但易受動態物體干擾,且要求場景特征豐富。
多采用 ICP(Iterative Closest Point、NDT(Normal Distributions Transform) 求解 R R R 和 t t t。
ICP 通過迭代最近點匹配,最小化點對距離:
min ? R , t ∑ i = 1 N ∥ ( R ? P A , i + t ) ? P B , i ∥ 2 \min_{R,t} \sum_{i=1}^N \| (R \cdot P_{A,i} + t) - P_{B,i} \|^2 R,tmin?i=1∑N?∥(R?PA,i?+t)?PB,i?∥2
NDT(Normal Distributions Transform) 則將點云轉換為概率密度函數,通過優化概率分布相似性求解變換。
- 基于運動軌跡的標定:
利用雷達在運動過程中采集的數據,通過里程計或SLAM生成軌跡約束。一般是聯合優化多個雷達的外參和運動軌跡,再使用因子圖優化(Factor Graph Optimization)等方式進行優化,求解雷達之間的運動軌跡所匹配的 R R R 和 t t t。
這種方式適合動態環境卻可在線標定,但計算復雜度高,需高精度里程計支持。
注:實際工程落地時,可不用追求高難度的優化算法,可根據具體場景選擇合適的方式來進行標定
ICP匹配示例
在這篇文章中,我們可結合手動標定法與自動標定法聯調方式來確保標定精度,簡單操作是假設我們通過手動標定方式初步得到基準激光雷達與附屬激光雷達的相對坐標變換參數 R 0 R_0 R0? 和 t 0 t_0 t0? ,在此基礎上采用 G I C P GICP GICP、 I C P ICP ICP等基礎算法進行多次配準提高標定精度,得到最終的 R R R 和 t t t;
這里展示一個 I C P ICP ICP的使用示例:
按" 空格 "即可觀察迭代匹配的效果。
#include <pcl/console/time.h>
#include <pcl/io/ply_io.h>
#include <pcl/point_types.h>
#include <pcl/registration/icp.h>
#include <pcl/visualization/pcl_visualizer.h>#include <string>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));
}
/*** 此函數是查看器的回調。 當查看器窗口位于頂部時,只要按任意鍵,就會調用此函數。* 如果碰到“空格”; 將布爾值設置為true。* @param event* @param nothing*/
void keyboardEventOccurred(const pcl::visualization::KeyboardEvent& event,void* nothing) {if (event.getKeySym() == "space" && event.keyDown()) next_iteration = true;
}int main(int argc, char* argv[]) {// The point clouds we will be usingPointCloudT::Ptr cloud_in(new PointCloudT); // Original point cloudPointCloudT::Ptr cloud_tr(new PointCloudT); // Transformed point cloudPointCloudT::Ptr cloud_icp(new PointCloudT); // ICP output point cloud// 我們檢查程序的參數,設置初始ICP迭代的次數,然后嘗試加載PLY文件。// Checking program argumentsif (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; // Default number of ICP iterationsif (argc > 2) {// If the user passed the number of iteration as an argumentiterations = atoi(argv[2]);if (iterations < 1) {PCL_ERROR("Number of initial iterations must be >= 1\n");return (-1);}}pcl::console::TicToc time;time.tic();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;// 我們使用剛性矩陣變換來變換原始點云。// cloud_in包含原始點云。// cloud_tr和cloud_icp包含平移/旋轉的點云。// cloud_tr是我們將用于顯示的備份(綠點云)。// Defining a rotation matrix and translation vectorEigen::Matrix4d transformation_matrix = Eigen::Matrix4d::Identity();// A rotation matrix (see https://en.wikipedia.org/wiki/Rotation_matrix)double theta = M_PI / 8; // The angle of rotation in radianstransformation_matrix(0, 0) = std::cos(theta);transformation_matrix(0, 1) = -sin(theta);transformation_matrix(1, 0) = sin(theta);transformation_matrix(1, 1) = std::cos(theta);// A translation on Z axis (0.4 meters)transformation_matrix(2, 3) = 0.4;// Display in terminal the transformation matrixstd::cout << "Applying this rigid transformation to: cloud_in -> cloud_icp"<< std::endl;print4x4Matrix(transformation_matrix);// Executing the transformationpcl::transformPointCloud(*cloud_in, *cloud_icp, transformation_matrix);*cloud_tr = *cloud_icp; // We backup cloud_icp into cloud_tr for later use// 這是ICP對象的創建。 我們設置ICP算法的參數。// setMaximumIterations(iterations)設置要執行的初始迭代次數(默認值為1)。// 然后,我們將點云轉換為cloud_icp。// 第一次對齊后,我們將在下一次使用該ICP對象時(當用戶按下“空格”時)將ICP最大迭代次數設置為1。// The Iterative Closest Point algorithmtime.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 () functionstd::cout << "Applied " << iterations << " ICP iteration(s) in " << time.toc()<< " ms" << std::endl;// 檢查ICP算法是否收斂; 否則退出程序。// 如果返回true,我們將轉換矩陣存儲在4x4矩陣中,然后打印剛性矩陣轉換。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");return (-1);}// Visualizationpcl::visualization::PCLVisualizer viewer("ICP demo");// Create two vertically separated viewportsint 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 usingfloat bckgr_gray_level = 0.0; // Blackfloat txt_gray_lvl = 1.0 - bckgr_gray_level;// Original point cloud is whitepcl::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 greenpcl::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 redpcl::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 viewportviewer.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 colorviewer.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 orientationviewer.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 visualiserwhile (!viewer.wasStopped()) {viewer.spinOnce();// The user pressed "space" :if (next_iteration) {// The Iterative Closest Point algorithmtime.tic();// 如果用戶按下鍵盤上的任意鍵,則會調用keyboardEventOccurred函數。// 此功能檢查鍵是否為“空格”。// 如果是,則全局布爾值next_iteration設置為true,從而允許查看器循環輸入代碼的下一部分:調用ICP對象以進行對齊。// 記住,我們已經配置了該對象輸入/輸出云,并且之前通過setMaximumIterations將最大迭代次數設置為1。icp.align(*cloud_icp);std::cout << "Applied 1 ICP iteration in " << time.toc() << " ms"<< std::endl;// 和以前一樣,我們檢查ICP是否收斂,如果不收斂,則退出程序。if (icp.hasConverged()) {// printf(“ 033 [11A”);// 在終端增加11行以覆蓋顯示的最后一個矩陣是一個小技巧。// 簡而言之,它允許替換文本而不是編寫新行; 使輸出更具可讀性。// 我們增加迭代次數以更新可視化器中的文本值。printf("\033[11A"); // Go up 11 lines in terminal output.printf("\nICP has converged, score is %+.0e\n", icp.getFitnessScore());// 這意味著,如果您已經完成了10次迭代,則此函數返回矩陣以將點云從迭代10轉換為11。std::cout << "\nICP transformation " << ++iterations<< " : cloud_icp -> cloud_in" << std::endl;// 函數getFinalTransformation()返回在迭代過程中完成的剛性矩陣轉換(此處為1次迭代)。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 posess.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);
}
參考文獻
[1] 姜聿于——自動駕駛感知【激光雷達】:一、標定
[2] Segal A , Hhnel D , Thrun S .Generalized-ICP[J]. 2009.DOI:10.15607/RSS.2009.V.021.
[3] Kulmer D , Tahiraj I , Chumak A ,et al.Multi-LiCa: A Motion and Targetless Multi LiDAR-to-LiDAR Calibration Framework[J].IEEE, 2025.DOI:10.1109/MFI62651.2024.10705773.
…