激光雷达与相机标定
激光雷达与相机标定
激光雷达与相机的标定方法有:Autoware, apollo, lidar_camera_calibration, 与but_velodyne
本文介绍使用lidar_camera_calibration来进行激光雷达与相机的标定。
本人要标定的激光雷达为:VLP16,相机:INDEMIND相机
1.下载源码并编译
mkdir -p catkin_ws/src
cd catkin_ws/src
#1.下载源码
git clone https://github.com/ankitdhall/lidar_camera_calibration.git
#2.将依赖项aruco_ros,aruco_mapping移出到path/to/your/ros/workspace/src,如catkin_ws/src下
mv lidar_camera_calibration/dependencies/* .
#切换到ws下
cd ../
#3.依次执行以下编译命令
catkin_make -DCATKIN_WHITELIST_PACKAGES="aruco;aruco_ros;aruco_msgs"
catkin_make -DCATKIN_WHITELIST_PACKAGES="aruco_mapping;lidar_camera_calibration"
catkin_make -DCATKIN_WHITELIST_PACKAGES=""
source devel/setup.sh
2. 制作标定板
本人使用纸张打印,并粘贴到硬纸板上,作为标定板,如下图,硬纸板尺寸:15.5cm15.5cm,Aruco Marker的尺寸是10cm10cm,Marker外白边宽度是1cm。
悬挂如下图:注意:标定板的悬挂四周应做到没有其他障碍物,否则激光雷达扫描标定点会多出额外噪声点云。
Aruco Marker图使用https://chev.me/arucogen/打印,参数选择:Original Aruco,id:26与582,size:100
本人写了一个简单的ros下的Aruco Marker识别和定位aruco_test_demo,
3.配置
需要修改的文件有lidar_camera_calibration/launch/find_transform.launch文件,相机标定参数文件,lidar_camera_calibration/conf下的config_file.txt、lidar_camera_calibration.yaml及marker_coordinates.txt文件。
find_transform.launch文件,如下:
<?xml version="1.0"?>
<!--find_transform.launch-->
<launch>
<!-- <param name="/use_sim_time" value="true"/> -->
<!-- 1.取消aruco_mapping node 注释,启动ArUco mapping -->
<!-- ArUco mapping -->
<node pkg="aruco_mapping" type="aruco_mapping" name="aruco_mapping" output="screen">
<!-- 2. 将topic /image_raw 映射为要标定相机的发出的/topic -->
<remap from="/image_raw" to="/imsee/image/right"/>
<!-- 3. 指定相机的标定参数文件 -->
<param name="calibration_file" type="string" value="$(find aruco_mapping)/data/inde_right_uurmi.ini" />
<!-- 4. 修改及核对 num_of_markers 和 marker_size值-->
<param name="num_of_markers" type="int" value="2" />
<param name="marker_size" type="double" value="0.1"/>
<param name="space_type" type="string" value="plane" />
<param name="roi_allowed" type="bool" value="false" />
</node>
<rosparam command="load" file="$(find lidar_camera_calibration)/conf/lidar_camera_calibration.yaml" />
<node pkg="lidar_camera_calibration" type="find_transform" name="find_transform" output="screen">
</node>
</launch>
find_transform.launch文件中所需的相机的标定文件可以通过使用相机标定工具camera_calibration得到。
本人使用indemind左目的标定文件inde_right_uurmi.ini如下:
文件位置:lidar_camera_calibration/src/aruco_mapping/data/inde_left_uurmi.ini
# Prosilica camera intrinsics
[image]
width
640
height
400
[camera]
camera matrix
247.65608 0 326.63302
0 247.72697 204.65654
0 0 1
distortion
0.179675 -0.143149 -0.004252 0.000590 0.000000
rectification
0.9984642 0.00088467 0.05539361
0.0011239 0.99999018 0.00428773
-0.05538928 -0.00434341 0.99845539
projection
319.55669 0 364.74093 0
0 319.55669 156.69363 0
0 0 1 0
idar_camera_calibration/conf下的config_file.txt、lidar_camera_calibration.yaml及marker_coordinates.txt文件。
config_file.txt,如下:
640 400 #相机的像素值
-0.4 0.5 #激光雷达选择保留的点云的横向范围,单位m,第一行为横向,第二行纵向,第三行是深度,
-0.5 0.5 #激光雷达选择保留的点云的纵向范围
0 0.55 #激光雷达选择保留的点云的深度范围,本配置是保留激光雷达坐标系下左右在[-0.4m~0.5m] 上下在[-0.5m~0.5m] 深度在[0~0.55m]范围的点云,点云的范围选择,应该以足以包含标定板四周轮廓的点云为准。
0.0003 #点云的强度intensity阈值,本设置为低于0.0003 intensity的点云将会被舍弃
2 #aruco marker 的数量
0 #是否启用camera_info_topic,建议为0
247.656 0.0 326.633 0.0 #相机参数矩阵
0.0 247.727 204.657 0.0
0.0 0.0 1.0 0.0
100 #迭代次数
1.57 -1.57 0.0 #雷达相机初始偏转角
0 0 0 #雷达相机初始偏移量
0 #0为velodyne雷达
lidar_camera_calibration.yaml文件如下:
idar_camera_calibration:
camera_frame_topic: /imsee/image/right #换成相机发出的topic
camera_info_topic: /imsee/camera_info #相机的info topic,如果camera_info_topic为0
velodyne_topic: /velodyne_points #雷达发布节点
marker_coordinates.txt标定板的配置文件如下:
2 # marker数
15.5 #length (s1)
15.5 #breadth (s2)
1.0 #border_width_along_length (b1)
1.0 #border_width_along_breadth (b2)
10.0 #edge_length_of_ArUco_marker (e)
#---------------------------------
15.5 #下一个标定板配置
15.5
1.0
1.0
10.0
4. 启动
# 1.硬件连接并上电,启动相机及雷达驱动
roslaunch velodyne_pointcloud VLP16_points.launch
roslaunch imsee_ros_wrapper start.launch #请启动自己相机的ros node
# 2.启动find_transform
roslaunch lidar_camera_calibration inde_find_transform.launch
5. 过程操作
启动find_transform后,会弹出cloud窗口显示指定的雷达点云,需要使用鼠标指定标定板的边缘点云,polygon窗口则显示鼠标选中的方形框。顺时针选中包含每个Marker的每条边的四个点,如下图所示,1,2,3,4为单击示例,每单机一次,按任意键(如空格),再点击下一个点。选中4个点,polygen中会显示4个点组成的框以及选中的点云。
完成标定板边缘点云选择后,会迭代计算相机与雷达的变换关系。
结果如下
After 99 iterations
--------------------------------------------------------------------
Average translation is:
-0.0674485
0.0784422
0.807537
Average rotation is:
0.990301 -0.0986281 0.0978547
-0.0741557 -0.970825 -0.228033
0.11749 0.218565 -0.968724
Average transformation is:
0.990301 -0.0986281 0.0978547 -0.0674485
-0.0741557 -0.970825 -0.228033 0.0784422
0.11749 0.218565 -0.968724 0.807537
0 0 0 1
Final rotation is:
0.0986432 -0.990301 0.0978396
-0.228092 0.0732011 0.970884
-0.96863 -0.118088 -0.218659
Final ypr is:
1.97898
1.82194
0.495174
Average RMSE is: 0.168414
RMSE on average transformation is: 0.169207
遇到问题
- 卡在Reading CameraInfo from configuration file
请检查自己的topic是否都映射成功,相机雷达是否都已启动,aruco_mapping是否启动成功。 - cloud窗口不能选中的问题
单机cloud上的像素点后,要按一下任意键(如空格等),再继续选中下一个像素点。
参考链接
https://blog.csdn.net/zhanghm1995/article/details/87802656
Autoware-https://blog.csdn.net/learning_tortosie/article/details/82347694
https://github.com/CPFL/Autoware
https://github.com/ApolloAuto/apollo/blob/master/docs/quickstart/apollo_2_0_sensor_calibration_guide.md
https://github.com/ankitdhall/lidar_camera_calibration
https://github.com/robofit/but_velodyne