SR-UKF 1.0
Square-Root Unscented Kalman Filter Library
Loading...
Searching...
No Matches
srukf Struct Reference

Square-Root Unscented Kalman Filter. More...

#include <srukf.h>

Public Attributes

srukf_workspacews
 
State Estimate

The current best estimate of the system state

srukf_matx
 
srukf_matS
 
Noise Covariances

Process and measurement noise, stored as square-roots

srukf_matQsqrt
 
srukf_matRsqrt
 
UKF Parameters

Tuning parameters controlling sigma point distribution

srukf_value alpha
 
srukf_value beta
 
srukf_value kappa
 
srukf_value lambda
 
Sigma Point Weights

Weights for reconstructing mean and covariance from sigma points

srukf_valuewm
 
srukf_valuewc
 

Detailed Description

Square-Root Unscented Kalman Filter.

This structure holds the complete state of an SR-UKF instance:

  • Current state estimate and its sqrt-covariance
  • Noise covariances (as square-roots)
  • UKF tuning parameters and derived weights
  • Pre-allocated workspace for efficiency

Key insight: We store \(S\) where \(P = SS^T\), not \(P\) itself. This is the "square-root" in SR-UKF, providing numerical stability.

See also
srukf_create, srukf_create_from_noise

Definition at line 391 of file srukf.h.

Member Data Documentation

◆ alpha

srukf_value srukf::alpha

Spread of sigma points (typically 1e-3 to 1). Smaller values keep points closer to the mean.

Definition at line 417 of file srukf.h.

Referenced by srukf_compute_weights(), and srukf_set_scale().

◆ beta

srukf_value srukf::beta

Prior distribution knowledge (2.0 for Gaussian). Affects the zeroth covariance weight.

Definition at line 419 of file srukf.h.

Referenced by srukf_compute_weights(), and srukf_set_scale().

◆ kappa

srukf_value srukf::kappa

Secondary scaling (typically 0 or 3-N). Can be used to ensure semi-positive definiteness.

Definition at line 421 of file srukf.h.

Referenced by srukf_set_scale().

◆ lambda

srukf_value srukf::lambda

Computed: \(\alpha^2 (N + \kappa) - N\). Determines actual sigma point spread.

Definition at line 423 of file srukf.h.

Referenced by srukf_compute_weights(), srukf_correct_core(), srukf_predict_core(), and srukf_set_scale().

◆ Qsqrt

srukf_mat* srukf::Qsqrt

Sqrt of process noise covariance (N x N). Models uncertainty in the state transition. Larger values = less trust in the model.

Definition at line 405 of file srukf.h.

Referenced by srukf_free(), srukf_predict_core(), and srukf_set_noise().

◆ Rsqrt

srukf_mat* srukf::Rsqrt

Sqrt of measurement noise covariance (M x M). Models sensor noise. Larger values = less trust in measurements.

Definition at line 408 of file srukf.h.

Referenced by srukf_correct_core(), srukf_free(), srukf_meas_dim(), and srukf_set_noise().

◆ S

srukf_mat* srukf::S

Sqrt of state covariance (N x N, lower triangular). Satisfies \(P = SS^T\) where P is the covariance.

Definition at line 397 of file srukf.h.

Referenced by srukf_correct(), srukf_free(), srukf_get_sqrt_cov(), srukf_predict(), srukf_reset(), and srukf_set_sqrt_cov().

◆ wc

srukf_value* srukf::wc

Covariance weights (2N+1 elements). \(w^c_0 = w^m_0 + (1 - \alpha^2 + \beta)\), \(w^c_i = w^m_i\) for i>0. Note: \(w^c_0\) can be negative for small alpha!

Definition at line 434 of file srukf.h.

Referenced by srukf_compute_weights(), srukf_correct_core(), srukf_free(), and srukf_predict_core().

◆ wm

srukf_value* srukf::wm

Mean weights (2N+1 elements). \(w^m_0 = \frac{\lambda}{N+\lambda}\), \(w^m_i = \frac{1}{2(N+\lambda)}\) for i>0

Definition at line 431 of file srukf.h.

Referenced by srukf_compute_weights(), srukf_correct_core(), srukf_free(), and srukf_predict_core().

◆ ws

srukf_workspace* srukf::ws

Pre-allocated workspace (allocated on demand)

Definition at line 440 of file srukf.h.

Referenced by ensure_workspace(), srukf_alloc_workspace(), srukf_correct(), srukf_correct_core(), srukf_free_workspace(), srukf_predict(), and srukf_predict_core().

◆ x

srukf_mat* srukf::x

The documentation for this struct was generated from the following file: