前言
为了后面的视觉激光融合SLAM以及跑通VINS-Fusion,需要标定双目相机和IMU得内参以及它们得外参(变换矩阵)。
准备工作
- 双目相机:ZED-m
- IMU:realsense-t265(仅使用它的imu信息)
- 系统:Ubuntu16.04 + ROS kinetic (ros推荐使用纯净的,就是新系统装ros,可以使用虚拟机)
双目相机标定
这里需要得到相机的内参矩阵,可以使用相机自带的标定信息,也可以使用标定工具包标定,比如VINS-Fusion,Kalibr,这里我以Kalibr为例。
Kalibr安装
因为后面联合标定也需要使用Kalibr,这里介绍一下它的安装。可以直接进Wiki看官方安装教程,教程写了两种安装方式,这里我们使用源码编译安装。官方使用的Ubuntu14.04+ ROS indigo,亲测Ubuntu16.04也行。
sudo apt install libv4l-dev
cd ~/kalibr_workspace/src
git clone https://github.com/ethz-asl/Kalibr.git
cd ~/kalibr_workspace
catkin_make
安装完成后我们进行测试,是否安装成功,这里生成一张标定板,为了能够使用A4纸打印,命令如下
roscore
rosrun kalibr kalibr_create_target_pdf --type checkerboard --nx 6 --ny 7 --csx 0.05 --csy 0.05
在当前目录下能找到生成的pdf(如图),按实际大小打印出来,每个格子应该是2.92cm 新建target_6x7.yaml保存参数
target_type: 'checkerboard'
targetCols: 6
targetRows: 7
rowSpacingMeters: 0.029
colSpacingMeters: 0.029
标定过程
- 将相机固定,在前方移动标定板大概十几秒,记录下bag包:
rosbag record /cmaera/image_1 /camera/image_2 -O camera.bag
这里可以降低相机的发布频率,减小包的大小和后面处理时间
- 进行标定
rosrun kalibr kalibr_calibrate_cameras --target target_6x7.yaml --bag cameara.bag --models pinhole-radtan pinhole-radtan --topics /cmaera/image_1 /camera/image_2 --show-extraction --bag-from-to 5 20 - 标定结果在当前目录生成
yaml 文件:
cam0:
cam_overlaps: [1]
camera_model: pinhole
distortion_coeffs: [0.0067221785223551735, 0.0006309071251854829, -0.0009206033732726818,
-0.005807607326385791]
distortion_model: radtan
intrinsics: [374.8798664259513, 376.62433296380203, 633.6382978832153, 368.203361863134]
resolution: [1280, 720]
rostopic: /zedm/zed_node/left/image_rect_color
cam1:
T_cn_cnm1:
- [0.9999958135540992, 0.0007219875640781401, 0.002802072131479685, -0.06140952719752661]
- [-0.0007241075974458178, 0.9999994523273698, 0.0007556541173352181, -0.0009541268599771967]
- [-0.0028015250239860137, -0.0007576799555491327, 0.9999957886804435, 0.0005387148522162342]
- [0.0, 0.0, 0.0, 1.0]
cam_overlaps: [0]
camera_model: pinhole
distortion_coeffs: [0.008041841705316074, 0.0003735182825901831, -0.001170616434022235,
-0.006061625440876723]
distortion_model: radtan
intrinsics: [373.7879644856689, 376.1467414780452, 632.7953296858204, 368.521883006889]
resolution: [1280, 720]
rostopic: /zedm/zed_node/right/image_rect_color
相机标定完成
IMU标定
IMU都有高斯白噪声和随机游走误差,这里使用港科大的imu_utils进行标定。
ceres-solver安装
因为工具需要ceres-solver支持,所以首先编译安装ceres-solver。
sudo apt-get install libgoogle-glog-dev libgflags-dev
sudo apt-get install libatlas-base-dev
sudo apt-get install libsuitesparse-dev
wget http://ceres-solver.org/ceres-solver-2.0.0.tar.gz
tar zxf ceres-solver-2.0.0.tar.gz
cd ceres-solver
mkdir build && cd build
cmake ..
make
sudo make install
-------------------------------------------
git clone https://github.com/eigenteam/eigen-git-mirror
cd eigen-git-mirror
mkdir build && cd build
cmake ..
sudo make install
--------------------------------------------
code_utils安装
sudo apt-get install libdw-dev
cd kalibr_workspace/src
git clone https://github.com/gaowenliang/code_utils.git
cd ..
catkin_make
报错解决:
backward.hpp No such file
- 将报错文件的
#include "backward.hpp" 改成#include "code_utils/backward.hpp"
‘integer_sequence’ is not a member of ‘std’
- 将CMakeLists.txt中的
set(CMAKE_CXX_FLAGS "-std=c++11") 改成 set(CMAKE_CXX_STANDARD 14)
imu_utils安装
cd kalibr_workspace/src
git clone https://github.com/gaowenliang/imu_utils.git
cd ..
catkin_make
注意一定要先编译code_utils再编译imu_utils
录取bag包
- 这里将IMU静置,录取bag包,官方建议是两个小时,时间短点也没事。
rosbag record /imu -O imu.bag
标定
- 在
imu_utils 包中新建一个launch 文件,格式如下:
<launch>
<node pkg="imu_utils" type="imu_an" name="imu_an" output="screen">
<param name="imu_topic" type="string" value= "/imu"/> # imu topic的名字
<param name="imu_name" type="string" value= "my_imu"/> # imu名字,和生成的标定结果文件名有关
<param name="data_save_path" type="string" value= "$(find imu_utils)/data/"/>
<param name="max_time_min" type="int" value= "120"/> #标定的时长,bag包时长
<param name="max_cluster" type="int" value= "100"/>
</node>
</launch>
roslaunch imu_utils imu.launch
rosbag play -r 200 imu.bag
- 大概不到一分钟就能出结果了,生成的
yaml 文件保存在imu_utils 的data 文件夹中,如下:
%YAML:1.0
---
type: IMU
name: my_imu
Gyr:
unit: " rad/s"
avg-axis:
gyr_n: 2.2484739538368025e-03
gyr_w: 3.5602903646558489e-05
x-axis:
gyr_n: 1.9584487136985310e-03
gyr_w: 2.2409337050820371e-05
y-axis:
gyr_n: 3.2136018308294412e-03
gyr_w: 6.1995884096858201e-05
z-axis:
gyr_n: 1.5733713169824356e-03
gyr_w: 2.2403489791996893e-05
Acc:
unit: " m/s^2"
avg-axis:
acc_n: 1.8278764625497403e-02
acc_w: 6.7504987254087304e-04
x-axis:
acc_n: 1.5158936655427320e-02
acc_w: 6.4629814567923399e-04
y-axis:
acc_n: 1.8054000063118674e-02
acc_w: 7.0841732570667293e-04
z-axis:
acc_n: 2.1623357157946221e-02
acc_w: 6.7043414623671254e-04
- 保存结果
为了后面的相机-IMU标定,我们需要gyr_n ,gyr_w ,acc_n ,acc_w 四个量,新建imu.yaml ,保存下来
rostopic: /imu
update_rate: 200.0
accelerometer_noise_density: 1.8278764625497403e-02
accelerometer_random_walk: 6.7504987254087304e-04
gyroscope_noise_density: 2.2484739538368025e-03
gyroscope_random_walk: 3.5602903646558489e-05
IMU标定完成
相机和IMU联合标定
-
把IMU和相机固定在一起录制bag 包,录制的时候需要充分激励IMU的各个轴,绕3个轴旋转和3个方向的平移 rosbag record /cmaera/image_1 /camera/image_2 /imu -o camera_imu.bag -
标定 rosrun kalibr kalibr_calibrate_imu_camera --target target_6x7.yaml --bag camera_imu.bag --cam camchain.yaml --imu imu.yaml --show-extraction --bag-from-to 5 45 -
运行时间会比较长,结果生成yaml文件,如下
cam0:
T_cam_imu:
- [0.9979030100755206, -0.03697544076091466, 0.05312625775218281, 0.014445441988765368]
- [-0.04740946675322602, -0.976335826957961, 0.21099927834115637, 0.010927983867985913]
- [0.044067277478760034, -0.213075502531028, -0.9760414464953624, -0.07194777524510915]
- [0.0, 0.0, 0.0, 1.0]
cam_overlaps: [1]
camera_model: pinhole
distortion_coeffs: [0.0067221785223551735, 0.0006309071251854829, -0.0009206033732726818,
-0.005807607326385791]
distortion_model: radtan
intrinsics: [374.8798664259513, 376.62433296380203, 633.6382978832153, 368.203361863134]
resolution: [1280, 720]
rostopic: /zedm/zed_node/left/image_rect_color
timeshift_cam_imu: 0.005640967418453902
cam1:
T_cam_imu:
- [0.9979880830532742, -0.03827724121820314, 0.0505434356605769, -0.04715785867130577]
- [-0.0480987303198019, -0.9764695294287694, 0.2102231439180307, 0.00990902333616146]
- [0.0413073628457973, -0.21223126749346238, -0.9763460405372905, -0.07145750657936548]
- [0.0, 0.0, 0.0, 1.0]
T_cn_cnm1:
- [0.9999958135540998, 0.0007219875640781401, 0.0028020721314796844, -0.06140952719752661]
- [-0.0007241075974458178, 0.9999994523273704, 0.000755654117335218, -0.0009541268599771967]
- [-0.0028015250239860133, -0.0007576799555491326, 0.9999957886804441, 0.0005387148522162342]
- [0.0, 0.0, 0.0, 1.0]
cam_overlaps: [0]
camera_model: pinhole
distortion_coeffs: [0.008041841705316074, 0.0003735182825901831, -0.001170616434022235,
-0.006061625440876723]
distortion_model: radtan
intrinsics: [373.7879644856689, 376.1467414780452, 632.7953296858204, 368.521883006889]
resolution: [1280, 720]
rostopic: /zedm/zed_node/right/image_rect_color
timeshift_cam_imu: 0.0038136751527354084
|