Étalonnage caméra-IMU avec Intel D435i

Deux outils ROS majeurs sont utilisés pour l'étalonnage de caméras et de capteurs IMU :

  • camera_calibration (ROS officiel) : idéal pour les caméras monoculaires ou stéréoscopiques. Il permet de calibrer les paramètres intrinsèques, la distorsion et l'extrinsèque relative entre deux caméras. Il fournit une interface graphique pour vérifier la détection du damier en temps réel.
  • Kalibr (ETH Zurich) : conçu pour les systèmes multi-caméras ou la fusion caméra-IMU. Il calibre à la fois les paramètres intrinsèques/extrinsèques des capteurs. Très utilisé en VIO (Visual-Inertial Odometry).

Les deux outils fonctionnent sous ROS. camera_calibration existe pour ROS1 et ROS2 ; Kalibr n'est compatible qu'avec ROS1 actuellement. L'installation de ROS peut être réalisée avec le script FishROS (une commande unique).

  1. Installation des outils

2.1. camera_calibration

sudo apt install ros-${ROS_DISTRO}-camera-calibration   # remplacer ${ROS_DISTRO} par melodic, humble, etc.

La commande est identique pour ROS1 et ROS2, seules les instructions d'exécution diffèrent légèrement.

2.2. Kalibr (compilation depuis les sources)

# Dépendances communes
sudo apt-get install -y \
    git wget autoconf automake nano \
    libeigen3-dev libboost-all-dev libsuitesparse-dev \
    doxygen libopencv-dev \
    libpoco-dev libtbb-dev libblas-dev liblapack-dev libv4l-dev

# Selon la version d'Ubuntu :
# 16.04
sudo apt-get install -y python2.7-dev python-pip python-scipy \
     python-matplotlib ipython python-wxgtk3.0 python-tk python-igraph python-pyx
# 18.04
sudo apt-get install -y python3-dev python-pip python-scipy \
     python-matplotlib ipython python-wxgtk4.0 python-tk python-igraph python-pyx
# 20.04
sudo apt-get install -y python3-dev python3-pip python3-scipy \
     python3-matplotlib ipython3 python3-wxgtk4.0 python3-tk python3-igraph python3-pyx

# Création de l'espace de travail
mkdir -p ~/kalibr_ws/src
cd ~/kalibr_ws
source /opt/ros/noetic/setup.bash   # adapter selon votre ROS1 (kinetic, melodic, noetic)
catkin init
catkin config --extend /opt/ros/noetic
catkin config --merge-devel
catkin config --cmake-args -DCMAKE_BUILD_TYPE=Release

# Clonage et compilation
cd ~/kalibr_ws/src
git clone https://github.com/ethz-asl/kalibr.git
cd ~/kalibr_ws
catkin build -DCMAKE_BUILD_TYPE=Release -j4   # -j4 selon le nombre de cœurs
  1. Matériel et logiciels testés

Élément Détail
Ubuntu 18.04 et 22.04
ROS Les deux versions (selon l'outil)
Pilotes caméra usb_cam et realsense-sdk
Capteurs Caméras industrielles mono/stéréo et D435i
  1. Étalonnage de la caméra

4.1. Avec camera_calibration

Utilisez un damier (méthode de Zhang) généré en ligne ou depuis wiki.ros. Lancez le nœud d’étalonnage après avoir démarré le pilote de la caméra :

# Mono
rosrun camera_calibration cameracalibrator.py --size 10x7 --square 0.015 image:=/camera/image_raw camera:=/camera

# Stéréo
rosrun camera_calibration cameracalibrator.py --size 10x7 --square 0.015 \
  right:=/stereo/right/image_raw left:=/stereo/left/image_raw \
  left_camera:=/stereo/left right_camera:=/stereo/right

Paramètres : --size : nombre de coins intérieurs (ex. 10x7). --square : côté d’un carré en mètres.

Déplacez le damier dans l’image (translation, rotation, profondeur) jusqu’à ce que les quatre barres de progression deviennent vertes. Cliquez sur Calibrate, puis Save.

Pour un système stéréo, la ligne de base se calcule à partir de la matrice de projection corrigée : baseline = -Tx / fx. Exemple :

# Caméra gauche
projection_matrix: ... data: [1635.195, 0, 632.694, 0, 0, 1635.195, 358.73, 0, 0, 0, 1, 0]
# Caméra droite
projection_matrix: ... data: [1635.195, 0, 632.694, -196.0455, 0, 1635.195, 358.73, 0, 0, 0, 1, 0]
# baseline = -(-196.0455) / 1635.195 ≈ 0.12 m

4.2. Avec Kalibr

Préférez une mire AprilGrid. Créez un fichier YAML de configuration :

# april_6x6.yaml
target_type: 'aprilgrid'
tagCols: 11
tagRows: 8
tagSize: 0.012       # en mètres
tagSpacing: 0.0036   # ratio espace/tag
codeOffset: 0

Lancez la caméra (ex. D435i) :

roslaunch realsense2_camera rs_camera.launch \
  color_width:=640 color_height:=480 color_fps:=30

Kalibr recommande 4 images/s. Si votre caméra ne peut pas descendre à 4 fps, utilisez topic_tools :

rosrun topic_tools throttle messages /camera/color/image_raw 4.0 /cam0/image_raw

Enregistrez un bag avec la mire déplacée devant la caméra (translations et rotations selon chaque axe) :

rosbag record /cam0/image_raw

Lancez l’étalonnage :

rosrun kalibr kalibr_calibrate_cameras \
  --target april_6x6.yaml \
  --bag 2024-11-11-11-11-11.bag \
  --bag-from-to 10 100 \
  --models pinhole-radtan \
  --topics /cam0/image_raw

Pour plusieurs caméras, ajoutez les modèles et topics correspondants. Les résultats sont sauvegardés dans un fichier YAML, TXT et PDF.

  1. Étalonnage de l'IMU (optionnel, non nécessaire pour la calibration conjointe)

5.1. Avec imu_utils

Cet outil léger nécessite Ceres Solver (version 1.14.0) et code_utils. Installation :

# Dépendances
sudo apt-get install liblapack-dev libsuitesparse-dev libcxsparse3 \
  libgflags-dev libgoogle-glog-dev libgtest-dev libdw-dev

# Téléchargement et compilation de Ceres
wget https://github.com/ceres-solver/ceres-solver/archive/refs/tags/1.14.0.tar.gz
tar -xzf 1.14.0.tar.gz
cd ceres-solver-1.14.0
mkdir build && cd build
cmake ..
make -j4
sudo make install

# Espace de travail pour imu_utils
mkdir -p ~/imu_calib_ws/src
cd ~/imu_calib_ws/src
git clone https://github.com/gaowenliang/code_utils.git
# Correction d'un include (dans sumpixel_test.cpp)
sed -i 's/#include "backward.hpp"/#include "code_utils\/backward.hpp"/' code_utils/src/sumpixel_test.cpp

cd ~/imu_calib_ws
catkin_make

# Version modifiée de imu_utils (correction d'unités)
cd ~/imu_calib_ws/src
git clone https://github.com/mintar/imu_utils.git
cd ~/imu_calib_ws
catkin_make

Enregistrez un bag de données IMU en statique (au moins 2 heures) :

roslaunch realsense2_camera rs_camera.launch gyro_fps:=200 accel_fps:=200
rosbag record /camera/imu --duration=2.5h

Créez un fichier launch :

<launch>
  <node pkg="imu_utils" type="imu_an" name="imu_an" output="screen">
    <param name="imu_topic" value="/camera/imu"/>
    <param name="imu_name" value="d435i"/>
    <param name="data_save_path" value="$(find imu_utils)/data/d435i/"/>
    <param name="max_time_min" value="120"/>
    <param name="max_cluster" value="100"/>
  </node>
</launch>

Exécutez :

roslaunch imu_utils d435i.launch
rosbag play -r 200 imu.bag

Les résultats sont dans $(find imu_utils)/data/d435i/. Exemple de fichier YAML produit :

%YAML:1.0
type: IMU
name: d435i
Gyr:
  unit: " rad/s"
  avg-axis:
    gyr_n: 2.149e-03   # bruit blanc
    gyr_w: 3.388e-05   # biais (random walk)
  ...
Acc:
  unit: " m/s^2"
  avg-axis:
    acc_n: 1.285e-02
    acc_w: 4.877e-04
  1. Étalonnage conjoint caméra-IMU

Le principe est similaire à l’étalonnage de la caméra avec Kalibr, mais on enregistre également les données IMU. Les fréquences recommandées : 20 fps pour la caméra, 200 fps pour l’IMU. Sur D435i, il faut activer l’IMU dans le launch file de realsense.

Enregistrez un bag en bougeant l’ensemble (caméra + IMU) devant la mire AprilGrid. Le mouvement doit inclure rotations et translations selon les trois axes.

Vous aurez besoin de quatre fichiers :

  • fichier YAML de la mire (ex. april_6x6.yaml)
  • fichier YAML des paramètres de la caméra (obtenu à l’étape 4.2)
  • fichier YAML des paramètres IMU (facultatif, Kalibr peut les estimer ; vous pouvez utiliser l’exemple imu_adis16448.yaml fourni par Kalibr)
  • le bag enregistré

Vérifiez que les noms de topics correspondent. Lancez la calibration :

rosrun kalibr kalibr_calibrate_imu_camera \
  --target april_6x6.yaml \
  --cam camchain.yaml \
  --imu imu_adis16448.yaml \
  --bag 2024-11-03-17-44-26.bag \
  --bag-from-to 5 135 \
  --show-extraction   # optionnel pour visualiser

Après la fin du calcul, quatre fichiers de résultats sont générés (PDF, TXT, YAML, etc.).

Étiquettes: Kalibr camera_calibration IMU D435i Realsense

Publié le 2 juin à 21h33