FixedLagSmoother

Introduction and Overview

This implements a fixed lag Kalman smoother.


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.FixedLagSmoother(dim_x, dim_z, N=None)[source]

Fixed Lag Kalman smoother.

Computes a smoothed sequence from a set of measurements based on the fixed lag Kalman smoother. At time k, for a lag N, the fixed-lag smoother computes the state estimate for time k-N based on all measurements made between times k-N and k. This yields a pretty good smoothed result with O(N) extra computations performed for each measurement. In other words, if N=4 this will consume about 5x the number of computations as a basic Kalman filter. However, the loops contain only 3 dot products, so it will be much faster than this sounds as the main Kalman filter loop involves transposes and inverses, as well as many more matrix multiplications.

Implementation based on Wikipedia article as it existed on November 18, 2014.

References

Wikipedia http://en.wikipedia.org/wiki/Kalman_filter#Fixed-lag_smoother

Simon, Dan. “Optimal State Estimation,” John Wiley & Sons pp 274-8 (2006).



Examples

from filterpy.kalman import FixedLagSmoother
fls = FixedLagSmoother(dim_x=2, dim_z=1)

fls.x = np.array([[0.],
                  [.5]])

fls.F = np.array([[1.,1.],
                  [0.,1.]])

fls.H = np.array([[1.,0.]])

fls.P *= 200
fls.R *= 5.
fls.Q *= 0.001

zs = [...some measurements...]
xhatsmooth, xhat = fls.smooth_batch(zs, N=4)

See my book Kalman and Bayesian Filters in Python https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python

__init__(dim_x, dim_z, N=None)[source]

Create a fixed lag Kalman filter smoother. You are responsible for setting the various state variables to reasonable values; the defaults below will not give you a functional filter.

Parameters:
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.

N : int, optional

If provided, the size of the lag. Not needed if you are only using smooth_batch() function. Required if calling smooth()

smooth(z, u=None)[source]

Smooths the measurement using a fixed lag smoother.

On return, self.xSmooth is populated with the N previous smoothed estimates, where self.xSmooth[k] is the kth time step. self.x merely contains the current Kalman filter output of the most recent measurement, and is not smoothed at all (beyond the normal Kalman filter processing).

self.xSmooth grows in length on each call. If you run this 1 million times, it will contain 1 million elements. Sure, we could minimize this, but then this would make the caller’s code much more cumbersome.

This also means that you cannot use this filter to track more than one data set; as data will be hopelessly intermingled. If you want to filter something else, create a new FixedLagSmoother object.

Parameters:
z : ndarray or scalar

measurement to be smoothed

u : ndarray, optional

If provided, control input to the filter

smooth_batch(zs, N, us=None)[source]

batch smooths the set of measurements using a fixed lag smoother. I consider this function a somewhat pedalogical exercise; why would you not use a RTS smoother if you are able to batch process your data? Hint: RTS is a much better smoother, and faster besides. Use it.

This is a batch processor, so it does not alter any of the object’s data. In particular, self.x is NOT modified. All date is returned by the function.

Parameters:
zs : ndarray of measurements

iterable list (usually ndarray, but whatever works for you) of measurements that you want to smooth, one per time step.

N : int

size of fixed lag in time steps

us : ndarray, optional

If provided, control input to the filter for each time step

Returns:
(xhat_smooth, xhat) : ndarray, ndarray

xhat_smooth is the output of the N step fix lag smoother xhat is the filter output of the standard Kalman filter