Types¶
Type definitions for state estimation filters.
Provides the core data types used across all estimation implementations:
- :class:
FilterState: Current filter state containing the state estimate and covariance matrix. - :class:
UKFConfig: Configuration for the Unscented Kalman Filter sigma point generation. - :class:
FilterResult: Output of a filter update step, containing the updated state plus diagnostic information for filter tuning.
All types are :class:~typing.NamedTuple instances, which JAX treats as
pytrees automatically. This means they work seamlessly with jax.jit,
jax.vmap, and jax.lax control flow primitives.
FilterResult
¶
Bases: NamedTuple
Result of a filter measurement update step.
Returned by ekf_update and ukf_update. Contains the updated
filter state along with diagnostic quantities useful for filter
tuning and health monitoring.
Attributes:
| Name | Type | Description |
|---|---|---|
state |
FilterState
|
Updated :class: |
innovation |
Array
|
Measurement residual |
innovation_covariance |
Array
|
Innovation covariance |
kalman_gain |
Array
|
Kalman gain matrix |
FilterState
¶
Bases: NamedTuple
State of a Kalman filter.
Holds the current state estimate and error covariance matrix. Returned
by ekf_predict, ukf_predict, and available as the state
field of :class:FilterResult.
Attributes:
| Name | Type | Description |
|---|---|---|
x |
Array
|
State estimate vector of shape |
P |
Array
|
Error covariance matrix of shape |
UKFConfig
¶
Bases: NamedTuple
Configuration for the Unscented Kalman Filter.
Controls the sigma point spread and weighting using the scaled unscented
transform (Van der Merwe). Default values alpha=1.0, beta=2.0,
kappa=0.0 produce unit-spread sigma points with well-conditioned
weights, robust for float32 across all state dimensions.
Attributes:
| Name | Type | Description |
|---|---|---|
alpha |
float
|
Spread of sigma points around the mean. |
beta |
float
|
Prior knowledge of the state distribution. |
kappa |
float
|
Secondary scaling parameter. |