标定相关的理论推导以及拓展知识请阅读知乎专栏文章:https://zhuanlan.zhihu.com/p/137501892
这是一个基于 ROS 的单线激光和相机外参数自动标定代码。标定原理如下图所示,相机通过二维码估计标定板平面在相机坐标系下的平面方程,由于激光点云落在平面上,将点云通过激光坐标系到相机坐标系的外参数 $ T_{cl} $ 转换到相机坐标系,构建点到平面的距离作为误差,使用非线性最小二乘进行求解。
mkdir LaserCameraCal_ws
mkdir ../src
cd src
git clone https://github.com/MegviiRobot/CamLaserCalibraTool
cd ..
catkin_make -DCMAKE_BUILD_TYPE=Release
强烈建议: 先用仿真数据试试这个标定系统,系统的可观性问题在仿真代码里都能找到验证,这样就能指导你如何采集数据。
cd LaserCameraCal_ws
source devel/setup.bash
rosrun lasercamcal_ros simulation_lasercamcal_node
特别地,请仔细阅读 main/calibr_simulation.cpp ,修改数据的生成观察系统的可观性。
请配置好 config/calibra_config.yaml 文件,里面有相机模型参数,rosbag 数据包的名字和保存路径,相机模型以及标定板的尺寸和类型等等。 具体请参考对应的 config.yaml。
采集激光数据制作 rosbag,请将标定板放于激光和相机前方 0.3m ~ 1.5m 左右,充分运动标定板(各个轴,各个角度,各个距离都充分运动)。
会把相机和标定板之间的姿态保存成一个 txt,用于后续标定。
cd LaserCameraCal_ws
source devel/setup.bash
roslaunch lasercamcal_ros kalibra_apriltag.launch
会自动检测激光在标定板上的线段,并完成标定和保存结果。
roslaunch lasercamcal_ros calibra_offline.launch
激光线条的自动获取如下图所示,其中红色部分为激光检测到的标定板线段,请注意保持激光前方是空旷区域:
roslaunch lasercamcal_ros debug.launch
rosbag play data.bag
运行 debug 工具,看激光光条和图像是否对齐的比较好。
2004, Qilong Zhang, Extrinsic Calibration of a Camera and Laser Range Finder (improves camera calibration).