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.

A zero-velocity update (ZUPT) allows OpenVINS to exploit knowledge that the sensor platform is momentarily stationary. Rather than attempting to triangulate features or track visual motion during a standstill — which is unreliable in monocular systems and vulnerable to dynamic objects — the system instead inserts a synthetic measurement that asserts zero acceleration and zero angular velocity. This soft constraint corrects bias estimates, prevents velocity drift, and keeps the filter consistent during periods where visual odometry would otherwise degrade.

What ZUPT Is and When It Applies

A ZUPT does not rigidly enforce zero velocity. Instead, it creates a synthetic observation of zero true acceleration and zero true angular rate, and updates the filter with that observation weighted by the expected measurement uncertainty. The result is a probabilistic constraint: if the IMU readings are consistent with being stationary, the filter is nudged toward zero velocity; if the readings are noisy or the threshold is not met, no update occurs. ZUPT is especially valuable in two scenarios:

Monocular VIO at Stop Lights

A wheeled vehicle stopped at a traffic light cannot triangulate features (no baseline change). Dynamic objects crossing the intersection corrupt feature tracks. ZUPT suppresses feature updates entirely and maintains state quality using only the inertial zero-velocity constraint.

Initialization Phases

During the first few seconds of operation, when the sliding window has too few clones for reliable triangulation, ZUPT can stabilize the IMU bias estimates and prevent early divergence.

The ZUPT Measurement Model

The synthetic measurement asserts that the true linear acceleration and angular velocity are zero: a=0,ω=0\mathbf{a} = \mathbf{0}, \qquad \boldsymbol{\omega} = \mathbf{0} Relating these to the IMU readings via the sensor model: a=ambaGIkRGgna\mathbf{a} = \mathbf{a}_m - \mathbf{b}_a - {}^{I_k}_G\mathbf{R}\,{}^G\mathbf{g} - \mathbf{n}_a ω=ωmbgng\boldsymbol{\omega} = \boldsymbol{\omega}_m - \mathbf{b}_g - \mathbf{n}_g The measurement residual is formed by subtracting the expected measurement from the synthetic “observation” of zero: z~=[a(ambaGIkRGgna)ω(ωmbgng)]=[(ambaGIkRGgna)(ωmbgng)]\tilde{\mathbf{z}} = \begin{bmatrix} \mathbf{a} - (\mathbf{a}_m - \mathbf{b}_a - {}^{I_k}_G\mathbf{R}\,{}^G\mathbf{g} - \mathbf{n}_a) \\ \boldsymbol{\omega} - (\boldsymbol{\omega}_m - \mathbf{b}_g - \mathbf{n}_g) \end{bmatrix} = \begin{bmatrix} -({\mathbf{a}_m - \mathbf{b}_a - {}^{I_k}_G\mathbf{R}\,{}^G\mathbf{g} - \mathbf{n}_a}) \\ -(\boldsymbol{\omega}_m - \mathbf{b}_g - \mathbf{n}_g) \end{bmatrix} The measurement Jacobians with respect to the relevant state variables are: z~GIkR=GIkRGg×,z~ba=z~bg=I3×3\frac{\partial\tilde{\mathbf{z}}}{\partial{}^{I_k}_G\mathbf{R}} = -\lfloor{}^{I_k}_G\mathbf{R}\,{}^G\mathbf{g}\times\rfloor, \qquad \frac{\partial\tilde{\mathbf{z}}}{\partial\mathbf{b}_a} = \frac{\partial\tilde{\mathbf{z}}}{\partial\mathbf{b}_g} = -\mathbf{I}_{3\times3} The 6×16\times1 residual and its Jacobians are then used in a standard EKF update, directly constraining the orientation (through the gravity rotation term), accelerometer bias, and gyroscope bias.
ZUPT does not strictly enforce zero velocity — it enforces zero acceleration and zero angular rate. This means a platform moving at constant velocity with zero acceleration will also pass the ZUPT test. A velocity magnitude check (zupt_max_velocity) is used as a secondary guard to prevent false detections at constant non-zero velocities.

Stationary Detection

Two complementary detection methods determine whether a ZUPT update should be applied at each timestep.

Disparity-Based Detection

Given two consecutive images, if the average pixel displacement of tracked feature points is below a threshold Δd\Delta d, the scene is assumed stationary: 1Ni=0Nuvk,iuvk1,i<Δd\frac{1}{N}\sum_{i=0}^{N}\|\mathbf{uv}_{k,i} - \mathbf{uv}_{k-1,i}\| < \Delta d This is fast and simple, but fails in dynamic environments where background features are static while other objects move (e.g., a car at a stop light with pedestrians crossing). The parameter zupt_max_disparity controls Δd\Delta d.

IMU-Based χ2\chi^2 Detection

The ZUPT residual itself is used as a test statistic. The normalized squared residual follows a χ2\chi^2 distribution under the zero-velocity hypothesis: z~(HPH+αR)1z~<χthreshold2\tilde{\mathbf{z}}^\top\bigl(\mathbf{H}\mathbf{P}\mathbf{H}^\top + \alpha\mathbf{R}\bigr)^{-1}\tilde{\mathbf{z}} < \chi^2_{\text{threshold}} where α\alpha is the noise inflation multiplier (zupt_noise_multiplier). In practice, the IMU noise matrix R\mathbf{R} must be inflated by a factor of α[50,100]\alpha \in [50, 100] for reliable detection. This large multiplier reflects either over-optimistic noise specifications in the IMU datasheet or additional vibrations (motor noise, road vibration) that are not captured by the nominal noise model.
For best results in vehicle applications, use both detection methods together: the disparity check provides a fast first-pass filter, and the IMU chi-squared test provides a principled statistical confirmation.

Configuration Parameters

ZUPT is configured in the OpenVINS YAML parameter file. The relevant parameters are:
ParameterTypeDescription
try_zuptboolEnable or disable the zero-velocity update. Set to true to activate ZUPT.
zupt_max_velocitydouble (m/s)Maximum velocity magnitude below which a ZUPT is considered. Prevents false detections at constant velocity. Typical value: 0.11.0 m/s.
zupt_noise_multiplierdoubleMultiplier α\alpha applied to the IMU noise matrix in the χ2\chi^2 test. Typical range: 50100.
zupt_max_disparitydouble (pixels)Maximum average feature disparity (in pixels) for the visual detection check. Typical value: 0.52.0 px.
zupt_only_at_beginningboolIf true, ZUPT is only applied during the first few seconds after initialization. Useful for recovering stable biases at startup without interfering with normal operation.

Example YAML Configuration

# Zero Velocity Update (ZUPT)
try_zupt: true
zupt_max_velocity: 0.5        # [m/s]  max velocity for ZUPT trigger
zupt_noise_multiplier: 50.0   # inflation factor for IMU noise in chi2 test
zupt_max_disparity: 1.0       # [pixels] max avg feature disparity
zupt_only_at_beginning: false  # apply ZUPT throughout the run

The UpdaterZeroVelocity Class

UpdaterZeroVelocity (ov_msckf/src/update/UpdaterZeroVelocity.h) implements the full detection and update pipeline.
class UpdaterZeroVelocity {
public:
  // Constructor: configures chi2 multiplier, IMU noises, disparity threshold,
  // max velocity, and provides access to the Propagator and feature database.
  UpdaterZeroVelocity(UpdaterOptions &options, NoiseManager &noises,
                      std::shared_ptr<ov_core::FeatureDatabase> db,
                      std::shared_ptr<Propagator> prop,
                      double gravity_mag, double zupt_max_velocity,
                      double zupt_noise_multiplier,
                      double zupt_max_disparity);

  // Feed incoming IMU data (mirrored from the main Propagator buffer).
  void feed_imu(const ov_core::ImuData &message, double oldest_time = -1);

  // Run detection + update. Returns true if a ZUPT was applied.
  bool try_update(std::shared_ptr<State> state, double timestamp);
};
try_update() proceeds as follows:
  1. Velocity check: if the current velocity estimate exceeds zupt_max_velocity, return false immediately.
  2. Disparity check: compute the average feature disparity from the feature database; if it exceeds zupt_max_disparity, return false.
  3. Build residual: form z~\tilde{\mathbf{z}} and H\mathbf{H} from the most recent IMU readings.
  4. Chi-squared test: evaluate the normalized residual; reject if above the 95th-percentile threshold.
  5. EKF update: apply the standard Kalman update with the ZUPT residual and Jacobians.
  6. Return true to signal that a ZUPT was applied (the caller can skip feature-based update for this frame).
When try_update() returns true, the main VIO pipeline in VioManager skips the normal MSCKF feature update for that timestamp. This prevents stale or dynamic-object-corrupted feature tracks from fighting against the zero-velocity constraint.

Build docs developers (and LLMs) love