Joint calibration of binocular camera and IMU

foreword

For the subsequent visual laser fusion SLAM and running through VINS-Fusion, it is necessary to calibrate the internal parameters of the binocular camera and IMU and their external parameters (transformation matrix).

Ready to work

  • Binocular Camera: ZED-m
  • IMU: realsense-t265 (just use its imu info)
  • System: Ubuntu16.04 + ROS kinetic (ros is recommended to use pure, that is, the new system is installed with ros, and a virtual machine can be used)

Binocular camera calibration

Here you need to get the internal parameter matrix of the camera, you can use the calibration information that comes with the camera, or you can use the calibration toolkit to calibrate, such as VINS-Fusion, Kalibr, here I take Kalibr as an example.

Kalibr installation

Because the subsequent joint calibration also needs to use Kalibr , here is its installation. You can go directly to the Wiki to see the official installation tutorial. The tutorial has written two installation methods. Here we use the source code to compile and install. Officially used Ubuntu14.04+ ROS indigo, you can also test Ubuntu16.04.

# 这里默认你已经做好了准备工作,比如创建工作空间kalibr_workspace,source了

# 安装libv4l,不然报错找不到libv4l
sudo apt install libv4l-dev

# 首先进入工作空间的src文件夹,克隆下源码
cd ~/kalibr_workspace/src
git clone https://github.com/ethz-asl/Kalibr.git

# 编译,时间有点长可以出去玩一下
cd ~/kalibr_workspace
catkin_make

After the installation is completed, we will test whether the installation is successful. Here, a calibration board is generated. In order to print on A4 paper, the command is as follows

# 启动rosmaster
roscore

# 生成标定板(7行6列,每个棋盘格宽0.05m)
rosrun kalibr kalibr_create_target_pdf --type checkerboard --nx 6 --ny 7 --csx 0.05 --csy 0.05

You can find the generated pdf in the current directory (as shown in the figure), print it out according to the actual size, each grid should be 2.92cm, create a
insert image description here
new target_6x7.yaml and save the parameters

target_type: 'checkerboard'
targetCols: 6
targetRows: 7
rowSpacingMeters: 0.029
colSpacingMeters: 0.029

Calibration process

  • Fix the camera, move the calibration board in front for about ten seconds, and record the bag:
    rosbag record /cmaera/image_1 /camera/image_2 -O camera.bag

Here you can reduce the release frequency of the camera, reduce the size of the package and the processing time

  • to calibrate
    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
    insert image description here

  • The calibration result generates a yamlfile in the current directory:
    insert image description here

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

Camera calibration completed


IMU calibration

IMUs have Gaussian white noise and random walk errors. Here, the imu_utils of HKUST is used for calibration.

ceres-solver installation

Because the tool requires ceres-solver support, first compile and install ceres-solver.

# 依赖安装
# google-glog + gflags
sudo apt-get install libgoogle-glog-dev libgflags-dev
# BLAS & LAPACK
sudo apt-get install libatlas-base-dev
# SuiteSparse and CXSparse (optional)
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

-------------------------------------------
# 这里如果报eigen3版本错误,就源码安装eigen3.3
git clone https://github.com/eigenteam/eigen-git-mirror

cd eigen-git-mirror
mkdir build && cd build
cmake ..
sudo make install
--------------------------------------------

code_utils installation

# 安装依赖
sudo apt-get install libdw-dev

# 安装
cd kalibr_workspace/src
git clone https://github.com/gaowenliang/code_utils.git
cd ..
catkin_make

Error solution:

backward.hpp No such file

  • Change the error file #include "backward.hpp"to#include "code_utils/backward.hpp"

‘integer_sequence’ is not a member of ‘std’

  • Change in set(CMAKE_CXX_FLAGS "-std=c++11")CMakeLists.txt toset(CMAKE_CXX_STANDARD 14)

imu_utils installation

cd kalibr_workspace/src
git clone https://github.com/gaowenliang/imu_utils.git
# 将CMakeLists.txt中的 `set(CMAKE_CXX_FLAGS "-std=c++11")` 改成 `set(CMAKE_CXX_STANDARD 14)`

cd ..
catkin_make

Note that you must compile code_utils before compiling imu_utils

Admission bag

  • Let the IMU stand still here, and the bag will be admitted. The official recommendation is two hours, but a shorter time is fine.
    rosbag record /imu -O imu.bag

Calibration

  • Create a new file in the imu_utilspackage with the launchfollowing format:
<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>
  • start calibration
# 启动launch文件
roslaunch imu_utils imu.launch

# 以200倍数播放bag包
rosbag play -r 200 imu.bag
  • It takes about less than a minute to get the results, and the generated yamlfiles are saved in imu_utilsthe datafolder as follows:
%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
  • Save the result
    For the camera-IMU calibration later, we need four quantities, , , , create a new gyr_none gyr_w, acc_nand save itacc_wimu.yaml
rostopic: /imu
update_rate: 200.0 #Hz

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 calibration completed


Camera and IMU joint calibration

  • Fix the IMU and the camera together to record the bag. When recording, you need to fully stimulate the various axes of the IMU, rotate around 3 axes and translate in 3 directions
    rosbag record /cmaera/image_1 /camera/image_2 /imu -o camera_imu.bag

  • Calibration
    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

  • The running time will be longer , and the result will generate a yaml file, as follows

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

Guess you like

Origin blog.csdn.net/qq_34935373/article/details/122563824