archimedes.observers.KalmanFilterBase

class archimedes.observers.KalmanFilterBase(dyn: ~typing.Callable, obs: ~typing.Callable, Q: ~numpy.ndarray, R: ~numpy.ndarray, missing: ~typing.Callable[[~numpy.ndarray], bool] = <function _default_missing>)

Abstract base class for Kalman filter implementations.

This class defines the common interface for Kalman filters used in system identification and state estimation.

All Kalman filter implementations follow the discrete-time state-space model:

x[k+1] = f(t[k], x[k], *args) + w[k]    (dynamics)
y[k]   = h(t[k], x[k], *args) + v[k]    (observations)

where w[k] ~ N(0, Q) is process noise and v[k] ~ N(0, R) is measurement noise.

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) where nx is the state dimension. Must be positive semi-definite.

  • R (array_like) – Measurement noise covariance matrix of shape (ny, ny) where ny is the measurement dimension. Must be positive definite.

  • missing (callable, optional) – Function to check if a value is missing (default: always returns False). The function should accept a single argument and return a boolean indicating whether the measurement is considered missing or corrupted. The “correct” step will be skipped if the measurement is missing, and the filter step will return zero innovation with pure prediction for state and covariance.

nx

State dimension, derived from the shape of Q.

Type:

int

ny

Measurement dimension, derived from the shape of R.

Type:

int

Notes

This class is decorated with @struct.pytree_node, making it compatible with function transformations and enabling efficient automatic differentiation through the filter operations. The filter parameters can be modified using standard PyTree operations.

Subclasses must implement the abstract step method that performs one complete filtering step (prediction + update). The implementation details depend on the specific filtering algorithm (EKF, UKF, etc.).

The args parameter in function signatures allows passing additional arguments to both dynamics and observation functions, enabling time-varying parameters or external inputs.

Examples

>>> # Subclasses implement the filtering algorithm
>>> class CustomFilter(KalmanFilterBase):
...     def step(self, t, x, y, P, args=None):
...         # Implementation-specific filtering logic
...         return x_new, P_new, innovation
>>>
>>> # Define system dynamics and observations
>>> def f(t, x):
...     return np.array([x[0] + 0.1*x[1], 0.9*x[1]], like=x)
>>>
>>> def h(t, x):
...     return np.array([x[0]], like=x)
>>>
>>> # Create filter instance
>>> Q = np.eye(2) * 0.01  # Process noise
>>> R = np.array([[0.1]]) # Measurement noise
>>> kf = CustomFilter(dyn=f, obs=h, Q=Q, R=R)
>>>
>>> # Filter properties
>>> print(f"State dimension: {kf.nx}")
>>> print(f"Measurement dimension: {kf.ny}")

See also

ExtendedKalmanFilter

Extended Kalman Filter implementation

UnscentedKalmanFilter

Unscented Kalman Filter implementation

__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])

missing()

replace(**updates)

Returns a new object replacing the specified fields with new values.

step(t, x, y, P[, args])

Perform one step of the filter, combining prediction and update steps.

Attributes

nx

State dimension derived from process noise covariance matrix.

ny

Measurement dimension derived from measurement noise covariance matrix.

dyn

obs

Q

R