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.

VINS-Fusion is configured through a single YAML file that is passed as a launch argument. Every aspect of the estimator — which sensors are active, how features are tracked, how the optimizer is budgeted, and where results are written — is controlled from this file. The sections below document every parameter in the order they appear in the config, using the EuRoC stereo-inertial configuration as the canonical example.

Sensor mode

These parameters determine the sensor combination that the estimator uses. Setting imu: 0 with num_of_cam: 2 runs pure stereo odometry (no IMU). Setting imu: 1 with num_of_cam: 1 runs mono-inertial. Setting imu: 1 with num_of_cam: 2 runs the full stereo-inertial pipeline.
imu
number
default:"1"
Enable (1) or disable (0) IMU integration. When disabled, imu_topic, all IMU noise parameters, g_norm, estimate_td, and td are ignored, and extrinsic estimation is forced off.
num_of_cam
number
default:"2"
Number of cameras. Accepted values are 1 (monocular) or 2 (stereo). When set to 2, cam1_calib, image1_topic, and body_T_cam1 are required.

ROS topics and output

imu_topic
string
default:"/imu0"
ROS topic for IMU messages (sensor_msgs/Imu). Only read when imu: 1.
image0_topic
string
default:"/cam0/image_raw"
ROS topic for the first (or only) camera image stream (sensor_msgs/Image).
image1_topic
string
default:"/cam1/image_raw"
ROS topic for the second camera image stream. Required when num_of_cam: 2; ignored otherwise.
output_path
string
default:"~/output/"
Directory where VINS-Fusion writes its trajectory result file (vio.csv) and, when extrinsic estimation is enabled, extrinsic_parameter.csv. The directory must exist and be writable before launch.

Camera calibration

The estimator resolves camera calibration files relative to the directory containing the main config file. Set cam0_calib to the filename (not an absolute path) of the camera YAML produced by the bundled camodocal calibration tool. See Camera Calibration for how to generate these files.
cam0_calib
string
default:"cam0_mei.yaml"
Filename of the camera calibration YAML for the first camera. Must reside in the same directory as the main config file.
cam1_calib
string
default:"cam1_mei.yaml"
Filename of the camera calibration YAML for the second camera. Required when num_of_cam: 2.
image_width
number
default:"752"
Image width in pixels. Must match the resolution used during camera calibration and the resolution of incoming image messages.
image_height
number
default:"480"
Image height in pixels. Must match the resolution used during camera calibration and the resolution of incoming image messages.

Extrinsic parameters

The extrinsic transform expresses the pose of each camera in the IMU (body) frame. These are 4×4 homogeneous transformation matrices stored in OpenCV’s YAML matrix format.
estimate_extrinsic
number
default:"0"
Controls online extrinsic calibration:
  • 0 — Fixed. The values in body_T_cam0 / body_T_cam1 are trusted exactly and never modified.
  • 1 — Online refinement. The provided matrices are used as an initial guess and optimised during runtime. The refined result is written to extrinsic_parameter.csv in output_path.
  • 2 — No prior. Starts from identity and calibrates from scratch. Only use this if you have no extrinsic estimate at all; convergence is slower.
When imu: 0, this is forced to 0 regardless of what is written here.
body_T_cam0
object
4×4 homogeneous transformation matrix (IMU frame ← camera 0 frame), stored as a flattened row-major double array in OpenCV matrix format. The rotation block occupies the top-left 3×3; the translation (in metres) is in the rightmost column.
body_T_cam0: !!opencv-matrix
   rows: 4
   cols: 4
   dt: d
   data: [0.0148655429818, -0.999880929698,  0.00414029679422, -0.0216401454975,
           0.999557249008,   0.0149672133247,  0.025715529948,  -0.064676986768,
          -0.0257744366974,  0.00375618835797, 0.999660727178,   0.00981073058949,
           0,                0,                0,                1]
body_T_cam1
object
4×4 homogeneous transformation matrix (IMU frame ← camera 1 frame). Required when num_of_cam: 2. Same format as body_T_cam0.
body_T_cam1: !!opencv-matrix
   rows: 4
   cols: 4
   dt: d
   data: [0.0125552670891, -0.999755099723,  0.0182237714554, -0.0198435579556,
           0.999598781151,   0.0130119051815,  0.0251588363115,  0.0453689425024,
          -0.0253898008918,  0.0179005838253,  0.999517347078,   0.00786212447038,
           0,                0,                0,                1]

Multi-threading

multiple_thread
number
default:"1"
Enable (1) or disable (0) multi-threaded processing. When enabled, feature tracking, back-end optimisation, and loop closure run in separate threads, improving throughput on multi-core systems. Disable for deterministic single-threaded replay or debugging.

Feature tracker

These parameters control the Lucas-Kanade optical-flow feature tracker that runs on every incoming image.
max_cnt
number
default:"150"
Maximum number of features to track simultaneously. Higher values improve observability but increase CPU cost per frame. The KITTI configs use 200 for a wider-baseline stereo rig.
min_dist
number
default:"30"
Minimum pixel distance between any two tracked features. Acts as a spatial suppression radius to ensure even distribution across the image. Measured in pixels.
freq
number
default:"10"
Rate (Hz) at which the feature tracking result is published as a ROS topic. Must be at least 10 Hz for reliable initialisation. Set to 0 to publish at the same rate as the incoming images.
F_threshold
number
default:"1.0"
RANSAC reprojection error threshold in pixels used when computing the fundamental matrix to reject outlier features. Increase if many features are incorrectly rejected on a low-resolution camera.
show_track
number
default:"1"
Publish (1) or suppress (0) the debug tracking image on the /feature_tracker/feature_img topic. Useful for visualising feature distribution; disable to reduce bandwidth.
flow_back
number
default:"1"
Enable (1) forward-backward optical flow consistency check. Each feature tracked from frame t to t+1 is tracked back to t, and features whose round-trip error exceeds a threshold are discarded. Improves tracking accuracy at the cost of roughly 30–40 % additional optical-flow compute time.

Optimization

max_solver_time
number
default:"0.04"
Wall-clock time budget for the Ceres non-linear least-squares solver, in seconds. The solver stops after this many seconds regardless of whether convergence criteria have been met, ensuring real-time operation. The EuRoC configs use 0.04 s (40 ms); the KITTI configs use 0.08 s.
max_num_iterations
number
default:"8"
Maximum number of Ceres solver iterations per optimisation window. Acts as a secondary bound alongside max_solver_time. The solver stops at whichever limit is hit first.
keyframe_parallax
number
default:"10.0"
Minimum average feature parallax (in pixels) required to insert a new keyframe. Internally divided by the focal length constant (460.0) to obtain a normalised threshold. Larger values produce a sparser keyframe graph; smaller values result in more frequent keyframes and higher memory usage.

IMU parameters

Accurate IMU noise parameters are critical for correct pre-integration and initialisation. The values below come from IMU datasheets or Allan variance analysis. See IMU Noise Parameters for detailed guidance.
acc_n
number
default:"0.1"
Accelerometer measurement noise standard deviation, in m/s² / √Hz. Corresponds to the white-noise floor of the accelerometer’s power spectral density.
gyr_n
number
default:"0.01"
Gyroscope measurement noise standard deviation, in rad/s / √Hz. Corresponds to the white-noise floor of the gyroscope’s power spectral density.
acc_w
number
default:"0.001"
Accelerometer bias random walk noise standard deviation, in m/s³ / √Hz. Characterises how quickly the accelerometer bias drifts over time.
gyr_w
number
default:"0.0001"
Gyroscope bias random walk noise standard deviation, in rad/s² / √Hz. Characterises how quickly the gyroscope bias drifts over time.
g_norm
number
default:"9.81007"
Local gravitational acceleration magnitude in m/s². Used to initialise the gravity vector during the visual-inertial alignment step. EuRoC datasets use 9.81007; look up the value for your geographic location if precision matters.

Temporal calibration

A fixed time offset between camera and IMU timestamps can cause apparent motion blurring in the estimated trajectory. VINS-Fusion models this offset as td, where image_clock + td = IMU_clock.
estimate_td
number
default:"0"
Enable (1) online estimation of the camera-IMU time offset, or fix it (0) at the value given by td. When imu: 0, this is forced to 0.
td
number
default:"0.0"
Initial (or fixed) camera-to-IMU time offset in seconds. The relationship is: image_clock + td = IMU_clock. A positive value means image timestamps lag behind the IMU. When estimate_td: 1, this serves as the initial guess for online estimation.

Loop closure

load_previous_pose_graph
number
default:"0"
Load (1) a previously saved pose graph from pose_graph_save_path on startup. When enabled, past loop closures are reused immediately, enabling map reuse across sessions.
pose_graph_save_path
string
default:"~/output/pose_graph/"
Directory where the pose graph (keyframes, descriptors, and loop-closure edges) is saved and loaded. The directory must be writable. On shutdown the pose graph is persisted here automatically.
save_image
number
default:"1"
Save (1) the raw image patch alongside each keyframe descriptor in the pose graph, enabling visual verification of loop closures in the pose graph viewer. Set to 0 to reduce disk usage when visualisation is not needed.

Complete example: EuRoC stereo-inertial config

The following is the unmodified euroc_stereo_imu_config.yaml from the VINS-Fusion repository, suitable for running on any EuRoC MAV sequence with both cameras and the IMU active.
%YAML:1.0

#common parameters
#support: 1 imu 1 cam; 1 imu 2 cam: 2 cam;
imu: 1
num_of_cam: 2

imu_topic: "/imu0"
image0_topic: "/cam0/image_raw"
image1_topic: "/cam1/image_raw"
output_path: "~/output/"

cam0_calib: "cam0_mei.yaml"
cam1_calib: "cam1_mei.yaml"
image_width: 752
image_height: 480

# Extrinsic parameter between IMU and Camera.
estimate_extrinsic: 0   # 0  Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
                        # 1  Have an initial guess about extrinsic parameters. We will optimize around your initial guess.

body_T_cam0: !!opencv-matrix
   rows: 4
   cols: 4
   dt: d
   data: [0.0148655429818, -0.999880929698, 0.00414029679422, -0.0216401454975,
           0.999557249008, 0.0149672133247, 0.025715529948,  -0.064676986768,
           -0.0257744366974, 0.00375618835797, 0.999660727178, 0.00981073058949,
           0, 0, 0, 1]

body_T_cam1: !!opencv-matrix
   rows: 4
   cols: 4
   dt: d
   data: [0.0125552670891, -0.999755099723, 0.0182237714554, -0.0198435579556,
           0.999598781151, 0.0130119051815, 0.0251588363115, 0.0453689425024,
          -0.0253898008918, 0.0179005838253, 0.999517347078, 0.00786212447038,
          0, 0, 0, 1]

#Multiple thread support
multiple_thread: 1

#feature traker paprameters
max_cnt: 150            # max feature number in feature tracking
min_dist: 30            # min distance between two features
freq: 10                # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image
F_threshold: 1.0        # ransac threshold (pixel)
show_track: 1           # publish tracking image as topic
flow_back: 1            # perform forward and backward optical flow to improve feature tracking accuracy

#optimization parameters
max_solver_time: 0.04  # max solver itration time (ms), to guarantee real time
max_num_iterations: 8   # max solver itrations, to guarantee real time
keyframe_parallax: 10.0 # keyframe selection threshold (pixel)

#imu parameters       The more accurate parameters you provide, the better performance
acc_n: 0.1          # accelerometer measurement noise standard deviation.
gyr_n: 0.01         # gyroscope measurement noise standard deviation.
acc_w: 0.001        # accelerometer bias random work noise standard deviation.
gyr_w: 0.0001       # gyroscope bias random work noise standard deviation.
g_norm: 9.81007     # gravity magnitude

#unsynchronization parameters
estimate_td: 0                      # online estimate time offset between camera and imu
td: 0.0                             # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)

#loop closure parameters
load_previous_pose_graph: 0        # load and reuse previous pose graph; load from 'pose_graph_save_path'
pose_graph_save_path: "~/output/pose_graph/" # save and load path
save_image: 1                   # save image in pose graph for visualization prupose; you can close this function by setting 0

Build docs developers (and LLMs) love