prefacio
Para la posterior fusión láser visual SLAM y ejecución mediante VINS-Fusion, es necesario calibrar los parámetros internos de la cámara binocular e IMU y sus parámetros externos (matriz de transformación).
Listo para trabajar
- Cámara binocular: ZED-m
- IMU: realsense-t265 (solo use su información de imu)
- Sistema: Ubuntu16.04 + ROS kinetic (se recomienda usar ros puro, es decir, el nuevo sistema se instala con ros y se puede usar una máquina virtual)
Calibración de cámara binocular
Aquí debe obtener la matriz de parámetros internos de la cámara, puede usar la información de calibración que viene con la cámara, o puede usar el kit de herramientas de calibración para calibrar, como VINS-Fusion, Kalibr, aquí tomo Kalibr como ejemplo .
Instalación Kalibr
Debido a que la posterior calibración conjunta también necesita usar Kalibr , aquí está su instalación. Puede ir directamente a Wiki para ver el tutorial de instalación oficial. El tutorial ha escrito dos métodos de instalación. Aquí usamos el código fuente para compilar e instalar. Utilizado oficialmente Ubuntu14.04+ ROS indigo, también puede probar 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
Una vez completada la instalación, probaremos si la instalación es exitosa. Aquí, se genera una placa de calibración. Para imprimir en papel A4, el comando es el siguiente
# 启动rosmaster
roscore
# 生成标定板(7行6列,每个棋盘格宽0.05m)
rosrun kalibr kalibr_create_target_pdf --type checkerboard --nx 6 --ny 7 --csx 0.05 --csy 0.05
Puede encontrar el pdf generado en el directorio actual (como se muestra en la figura), imprimirlo de acuerdo con el tamaño real, cada cuadrícula debe tener 2,92 cm, crear un
nuevo target_6x7.yaml y guardar los parámetros
target_type: 'checkerboard'
targetCols: 6
targetRows: 7
rowSpacingMeters: 0.029
colSpacingMeters: 0.029
Proceso de calibración
- Fije la cámara, mueva la placa de calibración al frente durante unos diez segundos y grabe la bolsa:
rosbag record /cmaera/image_1 /camera/image_2 -O camera.bag
Aquí puede reducir la frecuencia de disparo de la cámara, reducir el tamaño del paquete y el tiempo de procesamiento
-
calibrar
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
-
El resultado de la calibración genera un
yaml
archivo en el directorio actual:
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
Calibración de la cámara completada
Calibración de IMU
Todas las IMU tienen ruido blanco gaussiano y errores de caminata aleatoria Aquí, el imu_utils de HKUST se usa para la calibración.
instalación ceres-solver
Debido a que la herramienta requiere compatibilidad con ceres-solver, primero compile e instale 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
--------------------------------------------
instalación de code_utils
# 安装依赖
sudo apt-get install libdw-dev
# 安装
cd kalibr_workspace/src
git clone https://github.com/gaowenliang/code_utils.git
cd ..
catkin_make
Solución de errores:
backward.hpp No hay tal archivo
- Cambie el archivo de errores
#include "backward.hpp"
a#include "code_utils/backward.hpp"
'integer_sequence' no es miembro de 'std'
- Cambio en
set(CMAKE_CXX_FLAGS "-std=c++11")
CMakeLists.txt aset(CMAKE_CXX_STANDARD 14)
instalación imu_utils
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
Tenga en cuenta que debe compilar code_utils antes de compilar imu_utils
Bolsa de admisión
- Deje que la IMU se detenga aquí, y la bolsa será admitida.La recomendación oficial es de dos horas, pero un tiempo más corto está bien.
rosbag record /imu -O imu.bag
Calibración
- Cree un nuevo archivo en el
imu_utils
paquete con ellaunch
siguiente formato:
<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>
- iniciar la calibración
# 启动launch文件
roslaunch imu_utils imu.launch
# 以200倍数播放bag包
rosbag play -r 200 imu.bag
- Se tarda menos de un minuto en obtener los resultados y los
yaml
archivos generados se guardan enimu_utils
ladata
carpeta de la siguiente manera:
%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
- Guarde el resultado
Para la calibración posterior de la IMU de la cámara, necesitamos cuatro cantidades, , , , cree unagyr_n
nueva y guárdelagyr_w
acc_n
acc_w
imu.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
Calibración de IMU completada
Calibración conjunta de cámara e IMU
-
Fije la IMU y la cámara juntas para grabar la bolsa. Al grabar, debe estimular completamente los diversos ejes de la IMU, girar alrededor de 3 ejes y traducir en 3 direcciones
rosbag record /cmaera/image_1 /camera/image_2 /imu -o camera_imu.bag
-
Calibración
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
-
El tiempo de ejecución será más largo y el resultado generará un archivo yaml, de la siguiente manera
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