|
SR-UKF 1.0
Square-Root Unscented Kalman Filter Library
|
Square-Root Unscented Kalman Filter. More...
#include <srukf.h>
Public Attributes | |
| srukf_workspace * | ws |
State Estimate | |
The current best estimate of the system state | |
| srukf_mat * | x |
| srukf_mat * | S |
Noise Covariances | |
Process and measurement noise, stored as square-roots | |
| srukf_mat * | Qsqrt |
| srukf_mat * | Rsqrt |
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_value * | wm |
| srukf_value * | wc |
Square-Root Unscented Kalman Filter.
This structure holds the complete state of an SR-UKF instance:
Key insight: We store \(S\) where \(P = SS^T\), not \(P\) itself. This is the "square-root" in SR-UKF, providing numerical stability.
| 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().
| 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().
| 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().
| 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().
| 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().
| 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().
| 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().
| 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().
| 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().
| 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().
| srukf_mat* srukf::x |
State estimate vector (N x 1)
Definition at line 396 of file srukf.h.
Referenced by srukf_correct(), srukf_free(), srukf_get_state(), srukf_predict(), srukf_reset(), srukf_set_noise(), srukf_set_scale(), srukf_set_state(), and srukf_state_dim().