Skip to main content

Documentation Index

Fetch the complete documentation index at: https://mintlify.com/rpng/open_vins/llms.txt

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

This tutorial walks you through running OpenVINS end-to-end on the EuRoC MAV Dataset, the most widely used benchmark for visual-inertial odometry. EuRoC provides synchronized monochrome stereo images at 20 Hz from two global-shutter cameras alongside a MEMS ADIS16448 IMU at 200 Hz. OpenVINS ships a ready-made configuration for this dataset, so no manual calibration is required. Before starting, make sure you have completed the installation guide and have a working build.

Configuration files

All OpenVINS parameters are driven by three YAML files. For EuRoC these are already provided under config/euroc_mav/ in the repository:
FilePurpose
estimator_config.yamlMain estimator settings: feature counts, SLAM options, zero-velocity update thresholds, etc.
kalibr_imu_chain.yamlIMU noise densities, random walk parameters, and ROS topic names
kalibr_imucam_chain.yamlCamera-to-IMU extrinsics, time offset, and camera intrinsics
You can override any estimator_config.yaml parameter directly from the launch file without editing the YAML file on disk.

Launch files

The ov_msckf/launch/ directory contains the following files:
FileDescription
subscribe.launchROS 1 launch — subscribes to live or bagged camera and IMU topics
subscribe.launch.pyROS 2 launch — equivalent subscriber node
simulation.launchRuns the built-in simulator (no dataset required)
serial.launchProcesses images in serial (useful inside Docker or slow machines)
display.rvizRViz configuration for ROS 1
display_ros2.rvizRViz configuration for ROS 2
display_driving.rvizRViz configuration for driving/vehicle datasets

Download the EuRoC bag

Download the V1_01_easy sequence (Vicon Room 1, easy trajectory) — a good starting point because it has low-dynamic motion and good lighting.
Download directly from the ASL server:
wget http://robotics.ethz.ch/~asl-datasets/ijrr_euroc_mav_dataset/vicon_room1/V1_01_easy/V1_01_easy.bag

Launch OpenVINS

Open three separate terminals. In the first, start a persistent ROS master so you do not have to restart RViz on each run:
# Terminal 0: ROS master
roscore
In a second terminal, source the workspace and launch the estimator:
# Terminal 1: OpenVINS estimator
source devel/setup.bash
roslaunch ov_msckf subscribe.launch config:=euroc_mav
The config:=euroc_mav argument resolves to config/euroc_mav/estimator_config.yaml automatically. The node name is run_subscribe_msckf and it subscribes to the camera and IMU topics listed in the config.You can override individual parameters at launch time without editing any file:
roslaunch ov_msckf subscribe.launch config:=euroc_mav use_stereo:=true max_cameras:=2
In the remaining two terminals, start RViz and then play the bag:
# Terminal 2: visualization
rviz -d ov_msckf/launch/display.rviz

# Terminal 3: data playback
rosbag play V1_01_easy.bag

Visualize in RViz

Once the bag starts playing you should see the following topics published in RViz:
  • Feature tracks — colored point cloud of tracked 2D feature positions projected into 3D
  • SLAM landmarks — persistent 3D map points maintained in the filter state
  • Pose estimate — 6-DOF camera/IMU pose as a TF frame and a PoseWithCovarianceStamped
  • Path — history of pose estimates drawn as a line
Open ov_msckf/launch/display.rviz (or display_ros2.rviz for ROS 2) from within RViz using File → Open Config if it does not load automatically.

Configuration overview

The estimator_config.yaml file exposes all key tuning knobs. Below are the most commonly adjusted parameters:
ParameterDefaultDescription
use_stereotrueUse both cameras in a stereo configuration
max_cameras2Number of cameras to use
num_pts200Maximum number of MSCKF feature tracks per frame
num_slam50Number of persistent SLAM features to maintain
dt_slam_delay2.0Seconds after init before SLAM features are added
try_zuptfalseEnable zero-velocity update
zupt_max_velocity1.0Max velocity (m/s) below which ZUPT is attempted
gravity_mag9.81Local gravity magnitude in m/s²
up_msckf_sigma_px1.0Pixel noise standard deviation for MSCKF updates
up_slam_sigma_px1.5Pixel noise standard deviation for SLAM updates
Start with the default EuRoC configuration before changing any parameters. The provided values are well-tuned for this dataset. When tuning for a new sensor, focus first on num_pts, up_msckf_sigma_px, and IMU noise parameters in kalibr_imu_chain.yaml.

Tuning tips

Check that the IMU noise parameters in kalibr_imu_chain.yaml match your sensor’s datasheet. Overly optimistic (too small) noise values cause the filter to over-trust the IMU and reject valid visual updates. Run kalibr_imu_validator or imu_utils to measure noise densities on your hardware.
This usually means the camera topic names in kalibr_imucam_chain.yaml do not match the topics in your bag. Run rosbag info <bag> (ROS 1) or ros2 bag info <bag> (ROS 2) to confirm the exact topic names, then update the config.
Set use_stereo:=false and max_cameras:=1 in the launch command. The EuRoC config uses both cameras by default; monocular mode works but produces less accurate depth estimates.
Reduce num_pts (e.g., to 100) and num_slam (e.g., to 25). You can also switch from the subscriber node to the serial node (serial.launch) which processes one frame at a time and is immune to scheduling delays.

Next steps

  • Try other EuRoC sequences (V1_02_medium, MH_01_easy, etc.) by downloading additional bags and passing the same config:=euroc_mav argument.
  • Explore other supported datasets (TUM-VI, UZH-FPV, KAIST Urban) in the Datasets guide.
  • Evaluate trajectory accuracy quantitatively using ov_eval — see the Evaluation overview.
  • Calibrate your own camera-IMU system following the Calibration guide.

Build docs developers (and LLMs) love