FadingKalmanFilter¶
Implements a fading memory 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.
Fading Memory Kalman filter
-
class
filterpy.kalman.
FadingKalmanFilter
(alpha, dim_x, dim_z, dim_u=0)[source]¶ Fading memory Kalman filter. This implements a linear Kalman filter with a fading memory effect controlled by alpha. This is obsolete. The class KalmanFilter now incorporates the alpha attribute, and should be used instead.
You are responsible for setting the various state variables to reasonable values; the defaults below will not give you a functional filter.
- Parameters
alpha : float, >= 1
alpha controls how much you want the filter to forget past measurements. alpha==1 yields identical performance to the Kalman filter. A typical application might use 1.01
dim_x : int
Number of state variables for the Kalman filter. For example, if you are tracking the position and velocity of an object in two dimensions, dim_x would be 4.
This is used to set the default size of P, Q, and u
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.
dim_u : int (optional)
size of the control input, if it is being used. Default value of 0 indicates it is not used.
Examples
See my book Kalman and Bayesian Filters in Python https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python
Attributes
log-likelihood of the last measurement.
Computed from the log-likelihood.
”
You will have to assign reasonable values to all of these before
running the filter. All must have dtype of float
x
(ndarray (dim_x, 1), default = [0,0,0…0]) state of the filter
P
(ndarray (dim_x, dim_x), default identity matrix) 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
(ndarray) Last measurement used in update(). Read only.
Q
(ndarray (dim_x, dim_x), default identity matrix) Process uncertainty matrix
R
(ndarray (dim_z, dim_z), default identity matrix) measurement uncertainty
H
(ndarray (dim_z, dim_x)) measurement function
F
(ndarray (dim_x, dim_x)) state transistion matrix
B
(ndarray (dim_x, dim_u), default 0) control transition matrix
y
(numpy.array) Residual of the update step. Read only.
K
(numpy.array(dim_x, dim_z)) Kalman gain of the update step. Read only.
S
( numpy.array) System uncertainty (P projected to measurement space). Read only.
S
( numpy.array) Inverse system uncertainty. Read only.
-
__init__
(alpha, dim_x, dim_z, dim_u=0)[source]¶ Initialize self. See help(type(self)) for accurate signature.
-
update
(z, R=None)[source]¶ Add a new measurement (z) to the kalman filter. If z is None, nothing is changed.
- Parameters
z : np.array
measurement for this update.
R : np.array, scalar, or None
Optionally provide R to override the measurement noise for this one call, otherwise self.R will be used.
-
predict
(u=0)[source]¶ Predict next position.
- Parameters
u : np.array
Optional control vector. If non-zero, it is multiplied by B to create the control input into the system.
-
batch_filter
(zs, Rs=None, update_first=False)[source]¶ Batch processes a sequences of measurements.
- Parameters
zs : list-like
list of measurements at each time step self.dt Missing measurements must be represented by ‘None’.
Rs : list-like, optional
optional list of values to use for the measurement error covariance; a value of None in any position will cause the filter to use self.R for that time step.
update_first : bool, optional,
controls whether the order of operations is update followed by predict, or predict followed by update. Default is predict->update.
- Returns
means: np.array((n,dim_x,1))
array of the state for each time step after the update. Each entry is an np.array. In other words means[k,:] is the state at step k.
covariance: np.array((n,dim_x,dim_x))
array of the covariances for each time step after the update. In other words covariance[k,:,:] is the covariance at step k.
means_predictions: np.array((n,dim_x,1))
array of the state for each time step after the predictions. Each entry is an np.array. In other words means[k,:] is the state at step k.
covariance_predictions: np.array((n,dim_x,dim_x))
array of the covariances for each time step after the prediction. In other words covariance[k,:,:] is the covariance at step k.
-
get_prediction
(u=0)[source]¶ Predicts the next state of the filter and returns it. Does not alter the state of the filter.
- Parameters
u : np.array
optional control input
- Returns
(x, P)
State vector and covariance array of the prediction.
-
residual_of
(z)[source]¶ returns the residual for the given measurement (z). Does not alter the state of the filter.
-
measurement_of_state
(x)[source]¶ Helper function that converts a state into a measurement.
- Parameters
x : np.array
kalman state vector
- Returns
z : np.array
measurement corresponding to the given state
-
property
alpha
¶ scaling factor for fading memory
-
property
log_likelihood
¶ log-likelihood of the last measurement.
-
property
likelihood
¶ Computed from the log-likelihood. The log-likelihood can be very small, meaning a large negative value such as -28000. Taking the exp() of that results in 0.0, which can break typical algorithms which multiply by this value, so by default we always return a number >= sys.float_info.min.
-
property
mahalanobis
¶ ” Mahalanobis distance of innovation. E.g. 3 means measurement was 3 standard deviations away from the predicted value.
- Returns
mahalanobis : float