archimedes.observers.ExtendedKalmanFilter¶
- class archimedes.observers.ExtendedKalmanFilter(dyn: ~typing.Callable, obs: ~typing.Callable, Q: ~numpy.ndarray, R: ~numpy.ndarray, missing: ~typing.Callable[[~numpy.ndarray], bool] = <function _default_missing>)¶
Extended Kalman Filter for nonlinear state estimation.
The Extended Kalman Filter (EKF) handles nonlinear dynamics and observation models by linearizing them around the current state estimate using Jacobian matrices. This makes it computationally efficient while providing reasonable performance for mildly nonlinear systems.
The EKF uses first-order Taylor series approximations:
F[k] ≈ ∂f/∂x |_{x[k|k-1]} (dynamics Jacobian) H[k] ≈ ∂h/∂x |_{x[k|k-1]} (observation Jacobian)
These Jacobians are computed using automatic differentiation for accuracy and efficiency.
- Parameters:
dyn (callable) – Dynamics function with signature
f(t, x, *args)
that returns the predicted state at the next time step. Must be compatible with automatic differentiation for gradient-based filters.obs (callable) – Observation function with signature
h(t, x, *args)
that maps state to expected measurements. Must be compatible with automatic differentiation for gradient-based filters.Q (array_like) – Process noise covariance matrix of shape
(nx, nx)
wherenx
is the state dimension. Must be positive semi-definite.R (array_like) – Measurement noise covariance matrix of shape
(ny, ny)
whereny
is the measurement dimension. Must be positive definite.
Notes
The EKF is most suitable for systems where:
Nonlinearities are mild (locally approximately linear)
Computational efficiency is important
The system dynamics and observations are smooth and differentiable
For highly nonlinear systems, consider using
UnscentedKalmanFilter
which can better capture nonlinear transformations of uncertainty.The EKF algorithm consists of two steps:
Prediction: Propagate state and covariance using linearized dynamics
Update: Incorporate measurements using linearized observation model
The linearization can introduce bias in the state estimates and may cause filter divergence if the nonlinearities are too strong or if the initial estimate is far from the true state.
Examples
>>> import numpy as np >>> from archimedes.observers import ExtendedKalmanFilter >>> >>> # Define nonlinear dynamics (simple pendulum) >>> def f(t, x): ... dt = 0.1 ... return np.hstack([ ... x[0] + dt * x[1], # position ... x[1] - dt * 9.81 * np.sin(x[0]) # velocity ... ]) >>> >>> # Define observations >>> def h(t, x): ... return x[0] >>> >>> # Create EKF >>> Q = np.eye(2) * 0.01 >>> R = np.array([[0.1]]) >>> ekf = ExtendedKalmanFilter(dyn=f, obs=h, Q=Q, R=R) >>> >>> # Filtering step >>> x = np.array([0.1, 0.0]) # Initial state >>> P = np.eye(2) * 0.1 # Initial covariance >>> y = np.array([0.12]) # Measurement >>> x_new, P_new, innov = ekf.step(0.0, x, y, P)
See also
KalmanFilterBase
Abstract base class for all Kalman filters
UnscentedKalmanFilter
Alternative for highly nonlinear systems
References
- __init__(dyn: ~typing.Callable, obs: ~typing.Callable, Q: ~numpy.ndarray, R: ~numpy.ndarray, missing: ~typing.Callable[[~numpy.ndarray], bool] = <function _default_missing>) None ¶
Methods
__init__
(dyn, obs, Q, R[, missing])correct
(t, x, y, P[, args])Perform the measurement update (correction) step of the EKF.
missing
()replace
(**updates)Returns a new object replacing the specified fields with new values.
step
(t, x, y, P[, args])Perform one complete EKF step (prediction + update).
Attributes
nx
State dimension derived from process noise covariance matrix.
ny
Measurement dimension derived from measurement noise covariance matrix.
dyn
obs
Q
R