联合标定
LiDAR-Camera Calibration using 3D-3D Point correspondences
简介
原项目来自LiDAR-Camera Calibration using 3D-3D Point correspondences,修改用于对相机和Robosense LiDAR联合标定。这里会简单写写标定步骤和我遇到的问题,我修改后的包已经放在了github上。
参考资料
- lidar_camera_calibration项目——激光雷达和相机联合标定
- SLAM学习笔记(二十一)3D雷达与相机的标定方法详细教程
- Velodyne-ZED-Calibration标定记录
- Aruco图案生成
其他依赖
标定步骤
camera_calibration
- 启动相机节点
- roslaunch capture_img run.launch 获取图片,使用MATLAB进行标定
lidar_camera_calibration
- create dir “/home/user/image_data/”
- 启动相机和激光雷达节点
- roslaunch lidar_camera_calibration start_lidar_camera.launch
- 启动aruco节点,检查是否能识别到标志
- roslaunch lidar_camera_calibration aruco.launch
- 启动标定节点
- roslaunch lidar_camera_calibration calibration.launch
Attention
-
注意Aruco标志的方向,要和原项目中保持一致。
-
sudo apt-get install ros-xxx-velodyne
-
将文件夹lidar_camera_calibration下的dependencies路径下的两个目录aruco_mapping和aruco_ros拷贝到ROS工作空间的src路径下,再进行编译。
-
find_transform.launch启动ArUco mapping节点并修改其中的重映射命令使得获取正确的相机图片话题
<remap from="/image_raw" to="xxx"/>
-
修改参数设置文件,主要是相机内参设置
-
注意一些文件被修改过(这里是因为我的两张ArUco图大小不一样,所以强行修改了源代码,如果两张图一样大小可以直接注释掉)
- aruco_mapping.cpp
if(vis_marker.id == 26) { vis_marker.scale.x = 0.23; vis_marker.scale.y = 0.23; } else if(vis_marker.id == 582) { vis_marker.scale.x = 0.24; vis_marker.scale.y = 0.24; } else { vis_marker.scale.x = marker_size_; vis_marker.scale.y = marker_size_; }
- markerdetector.cpp
if(detectedMarkers[i].id == 26) { //std::cout << "ID26" << std::endl; detectedMarkers[i].calculateExtrinsics ( 0.23,camMatrix,distCoeff,setYPerpendicular ); } else if(detectedMarkers[i].id == 582) { //std::cout << "ID582" << std::endl; detectedMarkers[i].calculateExtrinsics ( 0.24,camMatrix,distCoeff,setYPerpendicular ); } else { //std::cout << "wrong ID!!!!!!!!!!!!!!!!" << std::endl; detectedMarkers[i].calculateExtrinsics ( markerSizeMeters,camMatrix,distCoeff,setYPerpendicular ); }
-
启动标定节点前,需要保证aruco标记能够在相机画面内可见。
-
注意PreprocessUtils.h的lidar线数设置
std::vector <std::vector<myPointXYZRID *>> rings(16);
-
标定时注意如果是VNC远程连接工控机,需要外接键鼠直接标定,否则需要修改Corners.cpp代码。
while (collected != 3*LINE_SEGMENTS[q]) { cv::setMouseCallback("cloud", onMouse, &_point_); cv::imshow("cloud", image_edge_laser); cv::waitKey(0); ++collected; std::cout << "collected:" << collected << std::endl; if(collected%3==1) //for VNC connect polygon.push_back(_point_); }
标定后使用
这个坑我也是翻了原项目的issue才发现怎么解决。
主要用到Final Rotation和Average translation作为[R|t],其中final_rotation = rotation_avg * lidarToCamera