Skip to main content

Documentation Index

Fetch the complete documentation index at: https://mintlify.com/HKUST-Aerial-Robotics/Vins-Fusion/llms.txt

Use this file to discover all available pages before exploring further.

Visual-inertial odometry is as much a hardware problem as a software one. Before spending time tuning configuration parameters, it is worth ensuring your sensor rig meets the basic quality requirements that VINS-Fusion expects. This page walks through hardware selection, config file authoring, camera calibration, and IMU noise characterization—the four steps required to run VINS-Fusion on a custom device.

Hardware recommendations

VIO performance depends heavily on hardware quality. For first-time setups, use professional equipment with global shutter cameras and hardware-synchronized IMU. Rolling shutter cameras and software-synchronized sensors can work but require additional tuning and typically produce worse results.
Key requirements:
  • Global shutter cameras — Rolling shutter cameras introduce motion blur and per-row timing distortions that degrade feature tracking, especially at high angular velocities.
  • Hardware-synchronized IMU — The IMU clock must be tightly aligned with the camera exposure trigger. Software synchronization introduces variable latency that degrades the tightly-coupled optimization.
  • High frame rate — At least 20 Hz for the camera; 200 Hz or higher for the IMU.
  • Adequate overlap — For stereo configurations, ensure the stereo baseline and field of view provide sufficient parallax for the expected operating range.

Setup steps

1

Write a config file

Copy the closest matching example config as a starting point and edit it for your device. The EuRoC configs are a good template for aerial vehicles; the KITTI configs are better for ground vehicles.
cp ~/catkin_ws/src/VINS-Fusion/config/euroc/euroc_stereo_imu_config.yaml \
   ~/catkin_ws/src/VINS-Fusion/config/my_device/my_device_config.yaml
At minimum, update the following fields:
# Sensor mode
imu: 1           # 1 = IMU present, 0 = stereo only
num_of_cam: 2    # 1 = monocular, 2 = stereo

# ROS topic names — must match what your hardware publishes
imu_topic: "/imu0"
image0_topic: "/cam0/image_raw"
image1_topic: "/cam1/image_raw"   # only needed when num_of_cam: 2

# Path where VINS writes output files and pose graphs
output_path: "~/output/"

# Camera calibration files (relative to the config directory)
cam0_calib: "cam0.yaml"
cam1_calib: "cam1.yaml"           # only needed when num_of_cam: 2

# Image resolution — must match your calibration
image_width: 640
image_height: 480
The config file path is passed directly to vins_node at launch time, and camera calibration file paths inside the config are resolved relative to the config file’s directory. Keep calibration files in the same folder as your config.
2

Calibrate your cameras

VINS-Fusion uses the camodocal camera model library, which supports three projection models:
Model--camera-model valueTypical use
PinholepinholeStandard rectilinear lenses
Mei (unified)meiWide-angle and fisheye lenses
EquidistantequidistantFisheye / 180° lenses
Print a calibration target (12×8 asymmetric circle grid with 80 mm spacing is used in the provided example data). Place your calibration images in a directory called calibrationdata, then run:
cd ~/catkin_ws/src/VINS-Fusion/camera_models/camera_calib_example/
rosrun camera_models Calibrations -w 12 -h 8 -s 80 -i calibrationdata --camera-model pinhole
Substitute mei or equidistant for --camera-model if your lens requires it. The tool writes a YAML calibration file that you reference from your config.
Collect at least 30–50 calibration images covering different positions, angles, and distances from the target. Coverage near the image borders is especially important for accurate distortion estimates.
3

Set IMU noise parameters

The IMU section of the config file has four noise parameters. Accurate values improve estimator convergence and reduce bias drift. Obtain them from your IMU datasheet or from an Allan variance analysis:
# IMU noise parameters
acc_n: 0.1        # accelerometer measurement noise std dev (m/s²/√Hz)
gyr_n: 0.01       # gyroscope measurement noise std dev (rad/s/√Hz)
acc_w: 0.001      # accelerometer bias random walk std dev (m/s³/√Hz)
gyr_w: 0.0001     # gyroscope bias random walk std dev (rad/s²/√Hz)
g_norm: 9.81007   # local gravity magnitude (m/s²)
Setting noise values too low causes the estimator to over-trust IMU measurements, which makes it brittle to vibration. Setting them too high slows convergence. Use manufacturer-specified values as a starting point and tune if needed.
4

Set extrinsic parameters

The body_T_cam0 (and body_T_cam1 for stereo) fields define the rigid-body transform from the IMU frame to each camera frame as a 4×4 homogeneous matrix.
estimate_extrinsic: 1   # 0 = trust provided values exactly
                        # 1 = use as initial guess and optimize online

body_T_cam0: !!opencv-matrix
   rows: 4
   cols: 4
   dt: d
   data: [R00, R01, R02, tx,
          R10, R11, R12, ty,
          R20, R21, R22, tz,
          0,   0,   0,   1 ]
If you have precise factory calibration data, set estimate_extrinsic: 0. If your extrinsics are approximate, set it to 1 so VINS-Fusion refines the transform online during the first few seconds of motion.
5

Configure feature tracker settings

The defaults from the EuRoC config work well as a starting point:
max_cnt: 150          # maximum tracked features per frame
min_dist: 30          # minimum pixel distance between features
freq: 10              # tracking result publish rate (Hz); 0 = match camera
F_threshold: 1.0      # RANSAC inlier threshold (pixels)
show_track: 1         # publish tracking image for debugging
flow_back: 1          # bidirectional optical flow check
Reduce max_cnt on hardware with limited CPU budget. Increase min_dist in scenes with dense, repetitive texture.
6

Launch the estimator

Ensure your camera and IMU are publishing on the topics you specified in the config, then run:
# Terminal 1 — visualization
roslaunch vins vins_rviz.launch

# Terminal 2 — estimator
rosrun vins vins_node ~/catkin_ws/src/VINS-Fusion/config/my_device/my_device_config.yaml

# Terminal 3 — loop closure (optional)
rosrun loop_fusion loop_fusion_node ~/catkin_ws/src/VINS-Fusion/config/my_device/my_device_config.yaml
Your camera images must be published on IMAGE0_TOPIC (and IMAGE1_TOPIC for stereo), and IMU data on IMU_TOPIC, exactly as specified in the config.

Online temporal calibration

If your camera and IMU are not hardware-synchronized, enable online time-offset estimation:
estimate_td: 1    # estimate time offset online
td: 0.0           # initial guess (seconds); camera_time + td = IMU time
This adds a time-offset state to the optimization and can compensate for small, stable software-synchronization delays. It is not a substitute for hardware synchronization in high-dynamic environments.

Reference config templates

DatasetConfig pathMode
EuRoC MAV (stereo + IMU)config/euroc/euroc_stereo_imu_config.yamlAerial, indoor
EuRoC MAV (mono + IMU)config/euroc/euroc_mono_imu_config.yamlAerial, indoor
EuRoC MAV (stereo only)config/euroc/euroc_stereo_config.yamlAerial, indoor
KITTI Odometry (sequences 00–02)config/kitti_odom/kitti_config00-02.yamlOutdoor, driving
KITTI raw with GPSconfig/kitti_raw/kitti_10_03_config.yamlOutdoor, driving
Car democonfig/vi_car/vi_car.yamlOutdoor, driving
See the EuRoC example and KITTI example pages for the complete run commands used with these config files.

Build docs developers (and LLMs) love