EnsembleKalmanFilter¶
Introduction and Overview¶
This implements the Ensemble Kalman filter.
Copyright 2015 Roger R Labbe Jr.
FilterPy library. http://github.com/rlabbe/filterpy
Documentation at: https://filterpy.readthedocs.org
Supporting book at: https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python
This is licensed under an MIT license. See the readme.MD file for more information.
-
class
filterpy.kalman.
EnsembleKalmanFilter
(x, P, dim_z, dt, N, hx, fx)[source]¶ This implements the ensemble Kalman filter (EnKF). The EnKF uses an ensemble of hundreds to thousands of state vectors that are randomly sampled around the estimate, and adds perturbations at each update and predict step. It is useful for extremely large systems such as found in hydrophysics. As such, this class is admittedly a toy as it is far too slow with large N.
There are many versions of this sort of this filter. This formulation is due to Crassidis and Junkins [1]. It works with both linear and nonlinear systems.
Parameters: - x : np.array(dim_x)
state mean
- P : np.array((dim_x, dim_x))
covariance of the state
- dim_z : int
Number of of measurement inputs. For example, if the sensor provides you with position in (x,y), dim_z would be 2.
- dt : float
time step in seconds
- N : int
number of sigma points (ensembles). Must be greater than 1.
- K : np.array
Kalman gain
- hx : function hx(x)
Measurement function. May be linear or nonlinear - converts state x into a measurement. Return must be an np.array of the same dimensionality as the measurement vector.
- fx : function fx(x, dt)
State transition function. May be linear or nonlinear. Projects state x into the next time period. Returns the projected state x.
References
- [1] John L Crassidis and John L. Junkins. “Optimal Estimation of Dynamic Systems. CRC Press, second edition. 2012. pp, 257-9.
Examples
def hx(x): return np.array([x[0]]) F = np.array([[1., 1.], [0., 1.]]) def fx(x, dt): return np.dot(F, x) x = np.array([0., 1.]) P = np.eye(2) * 100. dt = 0.1 f = EnKF(x=x, P=P, dim_z=1, dt=dt, N=8, hx=hx, fx=fx) std_noise = 3. f.R *= std_noise**2 f.Q = Q_discrete_white_noise(2, dt, .01) while True: z = read_sensor() f.predict() f.update(np.asarray([z]))
See my book Kalman and Bayesian Filters in Python https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python
Attributes: - x : numpy.array(dim_x, 1)
State estimate
- P : numpy.array(dim_x, dim_x)
State covariance matrix
- x_prior : numpy.array(dim_x, 1)
Prior (predicted) state estimate. The *_prior and *_post attributes are for convienence; they store the prior and posterior of the current epoch. Read Only.
- P_prior : numpy.array(dim_x, dim_x)
Prior (predicted) state covariance matrix. Read Only.
- x_post : numpy.array(dim_x, 1)
Posterior (updated) state estimate. Read Only.
- P_post : numpy.array(dim_x, dim_x)
Posterior (updated) state covariance matrix. Read Only.
- z : numpy.array
Last measurement used in update(). Read only.
- R : numpy.array(dim_z, dim_z)
Measurement noise matrix
- Q : numpy.array(dim_x, dim_x)
Process noise matrix
- fx : callable (x, dt)
State transition function
- hx : callable (x)
Measurement function. Convert state x into a measurement
- K : numpy.array(dim_x, dim_z)
Kalman gain of the update step. Read only.
- inv : function, default numpy.linalg.inv
If you prefer another inverse function, such as the Moore-Penrose pseudo inverse, set it to that instead: kf.inv = np.linalg.pinv
-
__init__
(x, P, dim_z, dt, N, hx, fx)[source]¶ x.__init__(…) initializes x; see help(type(x)) for signature
-
initialize
(x, P)[source]¶ Initializes the filter with the specified mean and covariance. Only need to call this if you are using the filter to filter more than one set of data; this is called by __init__
Parameters: - x : np.array(dim_z)
state mean
- P : np.array((dim_x, dim_x))
covariance of the state