types.estimation.UKFResult
types.estimation.UKFResult()Unscented Kalman Filter (UKF) result.
UKF uses the unscented transform to propagate mean and covariance through nonlinear functions without computing Jacobians.
Fields
state_estimate : StateVector State estimate x̂[k] (nx,) covariance : CovarianceMatrix Error covariance P[k] (nx, nx) innovation : OutputVector Measurement innovation y[k] - ŷ[k] (ny,) sigma_points : StateTrajectory Sigma points used χᵢ (2nx+1, nx) weights_mean : ArrayLike Weights for mean computation wᵢᵐ (2nx+1,) weights_covariance : ArrayLike Weights for covariance computation wᵢᶜ (2*nx+1,)
Examples
>>> # Highly nonlinear system (bearings-only tracking)
>>> def dynamics(x, u):
... # State: [x_pos, y_pos, x_vel, y_vel]
... dt = 0.1
... F = np.array([[1, 0, dt, 0],
... [0, 1, 0, dt],
... [0, 0, 1, 0],
... [0, 0, 0, 1]])
... return F @ x
>>>
>>> def measurement(x):
... # Measure bearing angle only
... return np.array([np.arctan2(x[1], x[0])])
>>>
>>> # Create UKF with tuned parameters
>>> ukf = UnscentedKalmanFilter(
... dynamics_fn=dynamics,
... measurement_fn=measurement,
... Q=0.01 * np.eye(4),
... R=0.05 * np.eye(1),
... alpha=0.001, # Spread of sigma points
... beta=2.0, # Prior knowledge (2 = Gaussian)
... kappa=0.0 # Secondary scaling parameter
... )
>>>
>>> # Initialize
>>> ukf.initialize(x0=np.array([1.0, 1.0, 0.1, 0.1]), P0=np.eye(4))
>>>
>>> # Update
>>> result: UKFResult = ukf.update(y_measured)
>>>
>>> # Inspect sigma points (useful for debugging)
>>> sigma_points = result['sigma_points']
>>> print(f"Sigma points shape: {sigma_points.shape}") # (9, 4)
>>>
>>> # Visualize sigma point spread
>>> import matplotlib.pyplot as plt
>>> plt.scatter(sigma_points[:, 0], sigma_points[:, 1])
>>> plt.title("UKF Sigma Points")
>>>
>>> # Check weights
>>> w_mean = result['weights_mean']
>>> print(f"Weight sum: {np.sum(w_mean):.6f}") # Should be 1.0