Filters

UKF and IMM estimators for non-linear state estimation

class UKF

Unscented Kalman Filter with manifold-aware state estimation.

Parameters
model
System model defining process and measurement dynamics.
process_noise
Process noise covariance Q (tangent_dim × tangent_dim).
measurement_noise
Measurement noise covariance R (meas_dim × meas_dim).
initial_covariance
Initial error covariance P₀ (tangent_dim × tangent_dim).
initial_state
Initial state vector x₀ (state_dim,).
svd_decomposition
Use SVD for the matrix square root. If False, uses LDLT (faster but less robust). Default: True.
scaled_sigma_points
Use scaled (2n+1) sigma points instead of symmetric (2n). Default: True.
Properties
state
Current state estimate (state_dim,).
covariance
State error covariance P (tangent_dim × tangent_dim).
innovation_covariance
Innovation covariance S from the last correct() step.
process_noise
Process noise covariance Q.
measurement_noise
Measurement noise covariance R.
x
Current state estimate (state_dim,).
P
State error covariance P (tangent_dim × tangent_dim).
UKF.__init__
__init__( self, model: quak._core.UKFModel, process_noise: np.ndarray[tuple[Any, ...], np.dtype[np.float64]], measurement_noise: np.ndarray[tuple[Any, ...], np.dtype[np.float64]], initial_covariance: np.ndarray[tuple[Any, ...], np.dtype[np.float64]], initial_state: np.ndarray[tuple[Any, ...], np.dtype[np.float64]], svd_decomposition: bool = True, scaled_sigma_points: bool = True )
UKF.predict
predict( self, dt: float, control: np.ndarray[tuple[Any, ...], np.dtype[np.float64]] | None = None )

Propagate the state forward by dt seconds.

Parameters
dt
Time step in seconds.
control
Optional control input vector.
Returns

PredictionResult with `z_mean and S_zz` attributes.

UKF.correct
correct( self, measurement: np.ndarray[tuple[Any, ...], np.dtype[np.float64]], sensor: quak._core.MeasurementModel | None = None ) -> quak.ukf.UKF

Update the state with a measurement.

Parameters
measurement
Observation vector.
sensor
Optional standalone measurement model for multi-sensor fusion.
Returns

self, for method chaining.

UKF.set_state
set_state( self, state: np.ndarray[tuple[Any, ...], np.dtype[np.float64]], covariance: np.ndarray[tuple[Any, ...], np.dtype[np.float64]] ) -> quak.ukf.UKF

Override the current state and covariance.

Returns

self, for method chaining.

class IMMEstimator

Interacting Multiple Model estimator for maneuvering target tracking.

Runs multiple UKF sub-filters and fuses their estimates using

Markov switching probabilities.

**Explicit mode** — provide transition matrix directly::

imm = IMMEstimator(

models=[cv, ctrv],

process_noises=[Q_cv, Q_ctrv],

measurement_noise=R,

initial_covariance=P0,

initial_state=x0,

transition_matrix=T,

initial_probabilities=np.array([0.5, 0.5]),

)

**Auto mode** — uniform transition matrix from `p_same`::

imm = IMMEstimator(

models=[cv, ctrv],

process_noises=[Q_cv, Q_ctrv],

measurement_noise=R,

initial_covariance=P0,

initial_state=x0,

p_same=0.95,

)

Parameters
models
List of system models (one per sub-filter).
process_noises
Per-model process noise covariances.
measurement_noise
Shared measurement noise covariance R.
initial_covariance
Initial error covariance P₀.
initial_state
Initial state vector x₀.
transition_matrix
Markov transition matrix (n × n). Mutually exclusive with p_same.
initial_probabilities
Initial model probabilities. Defaults to uniform.
svd_decomposition
Use SVD for the matrix square root (default: True).
p_same
Probability of staying in same model. Mutually exclusive with transition_matrix.
probability_floor
Minimum model probability to prevent collapse (default: 0.01).
Properties
state
Fused state estimate (state_dim,).
covariance
Fused error covariance P (tangent_dim × tangent_dim).
model_probabilities
Current model probabilities (n_models,).
transition_matrix
Markov transition matrix (n_models × n_models).
num_models
Number of sub-models.
probability_floor
Minimum model probability to prevent collapse.
x
Fused state estimate (state_dim,).
P
Fused error covariance P (tangent_dim × tangent_dim).
mu
Current model probabilities (n_models,).
IMMEstimator.__init__
__init__( self, models: list[quak._core.UKFModel], process_noises: list[np.ndarray[tuple[Any, ...], np.dtype[np.float64]]], measurement_noise: np.ndarray[tuple[Any, ...], np.dtype[np.float64]], initial_covariance: np.ndarray[tuple[Any, ...], np.dtype[np.float64]], initial_state: np.ndarray[tuple[Any, ...], np.dtype[np.float64]], *, transition_matrix: np.ndarray[tuple[Any, ...], np.dtype[np.float64]] | None = None, initial_probabilities: np.ndarray[tuple[Any, ...], np.dtype[np.float64]] | None = None, svd_decomposition: bool = True, p_same: float | None = None, probability_floor: float = 0.01 )
IMMEstimator.predict
predict( self, dt: float, control: np.ndarray[tuple[Any, ...], np.dtype[np.float64]] | None = None )

Propagate all sub-filters forward by dt seconds.

Returns

PredictionResult with `z_mean and S_zz` attributes.

IMMEstimator.project_to
project_to(self, dt: float) -> quak._core.StateEstimate

Non-mutating shadow predict — returns projected state without modifying the filter.

Creates temporary copies of internal UKF filters, runs the full IMM predict

pipeline on them, and returns a StateEstimate. The original filter state

is untouched.

Parameters
dt
Time step to project forward.
Returns

StateEstimate with projected x, P, and model probabilities.

IMMEstimator.correct
correct( self, measurement: np.ndarray[tuple[Any, ...], np.dtype[np.float64]], sensor: quak._core.MeasurementModel | None = None ) -> quak.imm.IMMEstimator

Update all sub-filters with a measurement and fuse probabilities.

Returns

self, for method chaining.

IMMEstimator.model_state
model_state( self, index: int ) -> np.ndarray[tuple[Any, ...], np.dtype[np.float64]]

State estimate of the i-th sub-filter.

IMMEstimator.model_covariance
model_covariance( self, index: int ) -> np.ndarray[tuple[Any, ...], np.dtype[np.float64]]

Error covariance of the i-th sub-filter.