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.

OpenVINS includes a full visual-inertial simulator that generates synthetic camera and IMU measurements from a real recorded pose trajectory. Rather than replaying recorded sensor data, the simulator uses a smooth mathematical representation of the trajectory — a cubic SE(3) B-spline — to analytically compute true angular velocity, linear acceleration, and camera observations at any point in time. Gaussian noise and random-walk biases are then injected to model realistic sensor behavior. This makes the simulator a controlled environment for evaluating estimator consistency, testing calibration, and running Monte Carlo experiments without collecting new hardware data.

SE(3) B-Spline Trajectory Representation

At the core of the simulator is a cumulative cubic B-spline on SE(3) following the formulation of Mueggler et al. and Patron et al. A set of uniformly distributed control point poses sampled from a recorded trajectory defines the spline. The pose at any query time t_s is computed by interpolating between the four nearest control points:
T_GS(u(t_s)) = T_{G,i-1} · A_0 · A_1 · A_2

A_j = exp(B_j(u(t)) · Ω_{i-1+j, i+j})
Ω_{i-1,i} = log(T_{G,i-1}^{-1} · T_{G,i})

B_0(u) = (1/6)(5 + 3u - 3u² + u³)
B_1(u) = (1/6)(1 + 3u + 3u² - 2u³)
B_2(u) = (1/6)(u³)

u(t_s) = (t_s - t_i) / (t_{i+1} - t_i)
where exp(·) and log(·) are the SE(3) matrix exponential and logarithm (see ov_core::BsplineSE3). The spline is C²-continuous, meaning the first and second derivatives (velocity and acceleration) exist and are smooth everywhere. This smoothness is what makes it suitable for generating physically plausible IMU readings. The only required input to the simulator is a plain-text pose trajectory file. The simulator uniformly samples this trajectory to build the spline control points, then uses the spline for both inertial measurement generation and visual feature projection throughout the simulation.

Inertial Measurement Generation

The C²-continuity of the B-spline allows the simulator to compute the true angular velocity and linear acceleration of the IMU body frame analytically at each timestep. The true quantities are extracted as:
ω(t) = vee(R_GI(u)ᵀ · Ṙ_GI(u))
a(t) = R_GI(u)ᵀ · p̈_IinG(u)
where vee(·) extracts the vector part of a skew-symmetric matrix. These true values are then corrupted with the IMU noise model used throughout OpenVINS: Noise model (per scalar, per axis):
ω_m(t)        = ω(t) + b_ω(t) + σ_g / √Δt · N(0,1)
b_ω(t + Δt)   = b_ω(t)        + σ_bg · √Δt  · N(0,1)
a_m(t)        = a(t) + R(t)·g + b_a(t) + σ_a / √Δt · N(0,1)
b_a(t + Δt)   = b_a(t)        + σ_ba · √Δt  · N(0,1)
SymbolParameterYAML key
σ_gGyroscope white noise densitygyroscope_noise_density
σ_bgGyroscope random walkgyroscope_random_walk
σ_aAccelerometer white noise densityaccelerometer_noise_density
σ_baAccelerometer random walkaccelerometer_random_walk
Biases evolve as a random walk integrated forward at each IMU time step Δt. The simulator maintains independent Mersenne Twister PRNGs for IMU and camera noise, seeded from the sim_seed_measurements configuration value for full reproducibility.

Visual Feature Map and Bearing Measurements

Before generating frame-by-frame measurements, the simulator builds a 3D point feature map of the environment:
  1. The simulator steps along the spline at a fixed interval.
  2. At each step, it checks how many existing map features project into each camera’s field of view.
  3. If there are not enough visible features, it generates new ones by shooting random rays from the camera center and assigning random depths uniformly in [sim_min_feature_gen_dist, sim_max_feature_gen_dist] meters.
  4. New features are added to the global map so they can be re-observed in future frames.
At each camera frame, map features are projected into the current camera pose. A feature measurement is included only if the feature is:
  • Within the camera’s field of view (image bounds after distortion)
  • In front of the camera (positive depth)
  • Within the maximum scene distance threshold
Pixel noise sampled from a zero-mean Gaussian is added directly to the raw pixel coordinates of each projected feature.

Running the Simulator

The simulator is launched via the simulation.launch file in the ov_msckf package. All standard OpenVINS estimator parameters apply, plus a set of simulation-specific parameters in config/rpng_sim/estimator_config.yaml.
1

Source your workspace

source ~/catkin_ws/devel/setup.bash
2

Launch a basic simulation

Run a single simulation with the default TUM corridor trajectory:
roslaunch ov_msckf simulation.launch \
  verbosity:="INFO" \
  seed:="1" \
  dataset:="tum_corridor1_512_16_okvis.txt" \
  max_cameras:="1" \
  fej:="true" \
  dosave_pose:="true" \
  path_est:="/tmp/ov_estimate.txt" \
  path_gt:="/tmp/ov_groundtruth.txt"
3

Run with online calibration

Enable online calibration of camera extrinsics and time offset to test calibration performance:
roslaunch ov_msckf simulation.launch \
  verbosity:="WARNING" \
  seed:="1" \
  dataset:="tum_corridor1_512_16_okvis.txt" \
  max_cameras:="1" \
  fej:="true" \
  sim_do_calibration:="true" \
  sim_do_perturbation:="true" \
  dosave_pose:="true" \
  path_est:="/tmp/ov_estimate.txt" \
  path_gt:="/tmp/ov_groundtruth.txt"
4

Run a Monte Carlo batch

The provided batch scripts automate Monte Carlo experiments. Edit the save paths in the script before running:
# Tests VIO with/without online calibration and parameter perturbation
bash ov_msckf/scripts/run_sim_calib.sh

Simulation Configuration Options

The simulation-specific parameters live at the bottom of config/rpng_sim/estimator_config.yaml:
# Random seeds — set to different values for independent Monte Carlo runs
sim_seed_state_init: 0       # seed for initial state randomization
sim_seed_preturb: 0          # seed for parameter perturbation
sim_seed_measurements: 0     # seed for IMU and camera noise

# Whether to perturb the initial calibration parameters from their true values
sim_do_perturbation: false

# Path to the input pose trajectory (plain-text: timestamp, q_GtoI, p_IinG)
sim_traj_path: "src/open_vins/ov_data/sim/tum_corridor1_512_16_okvis.txt"

# Minimum distance traveled before re-using a trajectory segment
sim_distance_threshold: 1.1

# Sensor simulation rates
sim_freq_cam: 10    # camera frame rate (Hz)
sim_freq_imu: 400   # IMU sample rate (Hz)

# Feature depth range for map generation
sim_min_feature_gen_dist: 5.0   # minimum feature depth (meters)
sim_max_feature_gen_dist: 7.0   # maximum feature depth (meters)
The simulation also uses all standard estimator calibration flags. For calibration Monte Carlo studies, set calib_cam_extrinsics: true, calib_cam_intrinsics: true, and calib_cam_timeoffset: true along with sim_do_perturbation: true to perturb the initial calibration guess away from the true values.

Key Source Files

ov_core::BsplineSE3

The SE(3) B-spline implementation. Handles control point construction, pose interpolation, and derivative computation for velocity and acceleration.

ov_msckf::Simulator

The master simulator class. Wraps BsplineSE3 to generate IMU measurements, build the feature map, and produce camera projections with noise.

Build docs developers (and LLMs) love