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.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.
Sensor mode
These parameters determine the sensor combination that the estimator uses. Settingimu: 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.
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.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
ROS topic for IMU messages (
sensor_msgs/Imu). Only read when imu: 1.ROS topic for the first (or only) camera image stream (
sensor_msgs/Image).ROS topic for the second camera image stream. Required when
num_of_cam: 2; ignored otherwise.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. Setcam0_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.
Filename of the camera calibration YAML for the first camera. Must reside in the same directory as the main config file.
Filename of the camera calibration YAML for the second camera. Required when
num_of_cam: 2.Image width in pixels. Must match the resolution used during camera calibration and the resolution of incoming image messages.
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.Controls online extrinsic calibration:
0— Fixed. The values inbody_T_cam0/body_T_cam1are 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 toextrinsic_parameter.csvinoutput_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.
imu: 0, this is forced to 0 regardless of what is written here.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.4×4 homogeneous transformation matrix (IMU frame ← camera 1 frame). Required when
num_of_cam: 2. Same format as body_T_cam0.Multi-threading
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.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.Minimum pixel distance between any two tracked features. Acts as a spatial suppression radius to ensure even distribution across the image. Measured in pixels.
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.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.
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.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
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.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.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.Accelerometer measurement noise standard deviation, in m/s² / √Hz. Corresponds to the white-noise floor of the accelerometer’s power spectral density.
Gyroscope measurement noise standard deviation, in rad/s / √Hz. Corresponds to the white-noise floor of the gyroscope’s power spectral density.
Accelerometer bias random walk noise standard deviation, in m/s³ / √Hz. Characterises how quickly the accelerometer bias drifts over time.
Gyroscope bias random walk noise standard deviation, in rad/s² / √Hz. Characterises how quickly the gyroscope bias drifts over time.
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 astd, where image_clock + td = IMU_clock.
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.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 (
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.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 (
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 unmodifiedeuroc_stereo_imu_config.yaml from the VINS-Fusion repository, suitable for running on any EuRoC MAV sequence with both cameras and the IMU active.