- 单目相机的内参标定方法可参考上一篇博客,这里直接介绍激光雷达和相机的外参标定方法,需要用到相机内参标定的结果。
- 目前我成功的有两种方法:
(1)autoware_camera_lidar_calibrator : 不需要标定板,在图像和点云中手动人工点击9对相对应的点。
(2)Autoware的Calibration Toolkit模块 : 需要标定板,在雷达点云图中标注出图像中标定板的位置。
一、利用autoware_camera_lidar_calibrator进行联合标定
1.1 联合标定流程
- 运行LiDAR驱动(这里使用Velodyne的16线激光雷达):
roslaunch velodyne_pointcloud VLP16_points.launch
- 运行Camera驱动:
rosrun usb_cam usb_cam_node
- 启动LiDAR-Camera外参标定节点,此节点分别使用rviz和image_view2包中的clicked_point和screenpoint(此处需要加载相机的内参标定文件):
roslaunch autoware_camera_lidar_calibrator camera_lidar_calibration.launch intrinsics_file:=/home/buu/20200809_1639_autoware_camera_calibration.yaml image_src:=/usb_cam/image_raw
- 参数说明:
intrinsics_file:相机内参标定结果的yaml文件,需替换为自己的路径;
image_src:发布的图像信息的topic; - 启动后会出现一个显示已经纠正过的相机图像的弹框,如下图所示:(该弹框需要ROS的image_view2组件,报错找不到这个node的话apt装一下就好了)
- 启动rviz调出雷达扫描的点云图,通过寻找图像窗口中图像的像素点与雷达点云数据的对应关系完成标定:先点击图像上的像素点,然后在rviz中通过
publish point
工具点击雷达点云中对应的3D点,观察终端会输出相应的信息:
- 标注9组不同的点后会自动将生成的标定结果保存到home目录下,名称类似为:20200809_173004_autoware_lidar_camera_calibration.yaml。该文件包含内参和外参,可与Autoware的Calibration Publisher一起使用,以发布和对齐LiDAR与Camera之间的转换。
1.2 标定结果测试
得到联合标定的外参文件后,就可以利用视觉和点云的信息融合来对标定结果进行验证。这里主要有两个模块:点云到图像(points2image)、 图像到点云(image2points).
- 点云到图像(points2image):
!!!注意:由于Autoware默认的激光雷达的topic是/points_raw,而自己运行的雷达驱动的topic不一定是这个,比如我的就是/velodyne_points,因此需要将points2image节点中的雷达topic改为/velodyne_points:
(1)修改1:将路径autoware.ai/src/autoware/visualization/points2image/nodes/points2image/points2image.cpp中的points_topic = "/points_raw";
改为:points_topic = "/velodyne_points";
(2)修改2:将路径autoware.ai/src/autoware/visualization/points2image/nodes/points2image/main.cpp中的ROSSub<sensor_msgs::PointCloud2ConstPtr>* velodyne = new ROSSub<sensor_msgs::PointCloud2ConstPtr>("points_raw", 1000, 10, "points2image");
改为:ROSSub<sensor_msgs::PointCloud2ConstPtr>* velodyne = new ROSSub<sensor_msgs::PointCloud2ConstPtr>("velodyne_points", 1000, 10, "points2image");
(3)修改3:将路径autoware.ai/src/autoware/utilities/runtime_manager/scripts/points2image.launch中的<remap from="/points_raw" to="/sync_drivers/points_raw" if="$(arg sync)" />
改为:<remap from="/velodyne_points" to="/sync_drivers/points_raw" if="$(arg sync)" />
修改完成后需要重新编译autoware。
- 分别启动雷达和相机的驱动节点:
roslaunch velodyne_pointcloud VLP16_points.launch
rosrun usb_cam usb_cam_node
- 在autoware.ai下开三个终端,分别运行:
source install/setup.bash
rosrun points2image points2image
source install/setup.bash
roslaunch runtime_manager calibration_publisher.launch file:=/home/buu/20200809_173004_autoware_lidar_camera_calibration.yaml image_topic_src:=/usb_cam/image_raw
# file为LiDAR-Camera联合标定的外参文件;image_topic_src为发布的图像topic
source install/setup.bash
roslaunch runtime_manager runtime_manager.launch
- 执行完毕后,在Runtime Manager中点击RViz,选择Panels –> Add New Panel –> ImageViewerPlugin,然后在新窗口中选好Image Topic和Point Topic即可:
- 图像到点云(image2points):
这部分代码在/autoware.ai/src/autoware/core_perception/pixel_cloud_fusion这个pkg下面。实现的功能是建立将velodyne-16的点云投影到640×480的图像上面,如果点云投影的二维点在图像640×480范围内,那么就把这个三维激光雷达点的位置记下来,同时匹配图像上对应像素的颜色,变成pcl::XYZRGB点返回,并显示出来。
!!!注意:需要将图像和激光雷达的topic改为自己驱动发出的topic:
(1)修改1:将路径 /autoware.ai/src/autoware/core_perception/pixel_cloud_fusion/src/pixel_cloud_fusion.cpp中的
"points_src"="/points_raw"
改为:"/velodyne_points"
;
(2)修改2:(因为我在运行pixel_cloud_fusion这个节点时,总是出现Waiting for Image frame to be available.
所以我手动给image_frame_id_赋了值,大家可根据自己的实际情况酌情修改)将路径 /autoware.ai/src/autoware/core_perception/pixel_cloud_fusion/src/pixel_cloud_fusion.cpp中的image_frame_id_ = " ";
和image_frame_id_ = in_image_msg->header.frame_id;
都改为:image_frame_id_ = "/camera";
(3)修改3:将路径 /autoware.ai/src/autoware/core_perception/pixel_cloud_fusion/launch/pixel_cloud_fusion.launch中的image_rectifier节点注释掉,暂时不运行;将相应参数修改为:
<arg name="points_src" default="/velodyne_points" />
<arg name="image_src" default="/image_rectified" />
<arg name="camera_info_src" default="/camera_info" />
修改完成后需要重新编译autoware.
- 分别启动雷达和相机的驱动节点:
roslaunch velodyne_pointcloud VLP16_points.launch
rosrun usb_cam usb_cam_node
- 在autoware.ai下开两个终端,分别运行:
source install/setup.bash
roslaunch runtime_manager calibration_publisher.launch image_topic_src:=/usb_cam/image_raw file:=/home/buu/20200809_173004_autoware_lidar_camera_calibration.yaml
source install/setup.bash
roslaunch pixel_cloud_fusion pixel_cloud_fusion.launch
- 新开一个终端,运行rviz,即可看到如下所示画面:
二、利用Calibration Toolkit进行联合标定:
参考此博客利用SmartCAR中的Calibration Toolkit完成联合标定,本文用的标定板规格为:7×9(内角点的列×行)。代码在detection/calibration/calibration_camera_lidar文件夹下面。
- 编译好代码后,首先要启动摄像头和激光雷达的驱动节点:
roslaunch cv_camera cv_camera_driver.launch
roslaunch velodyne_pointcloud VLP16_points.launch
- 启动联合标定节点:
roslaunch calibration_camera_lidar camera_lidar_calib.launch
- 第一个对话框选择:/image_raw:
- 第二个对话框选择:camera-velodyne:
- Calibration Tool Kit打开后,点击Load加载相机的内参文件,要求文件类型为yml,因此需要将之前生成的yaml后缀改为yml;然后设置参数:Pattern Size(m)为0.1和0.1;Pattern Number为7和9(如果使用的标定板不是上文中的规格,请自行设定参数)。参数设置之后关闭Calibration Tool Kit,重启加载配置。
- 当MainWindow出现如下画面后,调整MainWindow中画面位置(具体操作指南,可以参考文档:
detection/calibration/calibration_camera_lidar/CalibrationToolkit_Manual.pdf 的2.3节):
- 右上角为激光雷达数据, 首先点击图像, 使用键盘上’b’键调浅背景颜色;利用键盘上各个功能键调整角度,使得激光雷达图像下可以看到棋盘:
- 点击右上角的Grab捕获单帧图片和点云,生成下半部分的摄像机和激光雷达两个图像。调整位置,在捕获单帧的点云上面,选取图片中对应标定板的位置,选取的是圆圈内的所有点,所包含的信息不仅仅只有点,还有平面法相量,标定的时候一定要确保法相量与平面是垂直的。找到后用鼠标左键标记,如果标记有误,鼠标右键取消:
- 不断重复以上操作,共标记10张左右图片即可。
- 标定完成后,点击右上角的”Calibrate”进行计算。
- 验证标定:点击MainWindow右上角的”Project”进行验证, 左下方图像中会出现根据计算结果生成的激光雷达和图像对应位置的数据,以红色散点表示。如果散点分布在标定板上,说明标定正确;如果散点不在标定板上,则需对右下方激光雷达重新标定:
- 如果有需要更新的标记,重复以上内容,直至验证通过。
- 保存结果:点击MainWindow左上方的”Save”,将结果保存到合适位置,生成yml类型的外参标定文件。对于下面的两个弹窗,都选择”NO”:
OK,标定完成啦!
- 验证:可参考上述第一种方法中的验证方式进行验证。
参考:
- https://blog.csdn.net/weixin_39652282/article/details/105832799?utm_medium=distribute.pc_relevant.none-task-blog-BlogCommendFromMachineLearnPai2-1.channel_param&depth_1-utm_source=distribute.pc_relevant.none-task-blog-BlogCommendFromMachineLearnPai2-1.channel_param
- https://blog.csdn.net/mxdsdo09/article/details/88370662
- https://blog.csdn.net/learning_tortosie/article/details/82347694
- https://blog.csdn.net/X_kh_2001/article/details/89163659?depth_1-utm_source=distribute.pc_relevant.none-task&utm_source=distribute.pc_relevant.none-task
- http://s1nh.org/post/calib-velodyne-camera/
- https://blog.csdn.net/AdamShan/article/details/81670732
- https://blog.csdn.net/liu_yanxiaobai/article/details/103586798
- https://blog.csdn.net/weixin_35695879/article/details/86666784?depth_1-utm_source=distribute.pc_relevant.none-task-blog-BlogCommendFromBaidu-1&utm_source=distribute.pc_relevant.none-task-blog-BlogCommendFromBaidu-1#t4
- https://github.com/Autoware-AI/autoware.ai/wiki/Calibration