Skip to content

Commit c8e2810

Browse files
committed
Improve UKF Documentation
GitHub #48. I added a full example, and pointed the reader to the tests subdirectory.
1 parent c9ff436 commit c8e2810

File tree

1 file changed

+44
-5
lines changed

1 file changed

+44
-5
lines changed

filterpy/kalman/UKF.py

Lines changed: 44 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@
3030

3131
class UnscentedKalmanFilter(object):
3232
# pylint: disable=too-many-instance-attributes
33-
# pylint: disable=C0103
33+
# pylint: disable=invalid-name
3434
r"""
3535
Implements the Scaled Unscented Kalman filter (UKF) as defined by
3636
Simon Julier in [1], using the formulation provided by Wan and Merle
@@ -72,16 +72,55 @@ class UnscentedKalmanFilter(object):
7272
7373
inv : function, default numpy.linalg.inv
7474
If you prefer another inverse function, such as the Moore-Penrose
75-
pseudo inverse, set it to that instead: kf.inv = np.linalg.pinv
75+
pseudo inverse, set it to that instead:
7676
77+
.. code-block:: Python
78+
79+
kf.inv = np.linalg.pinv
7780
7881
7982
Examples
8083
--------
8184
82-
See my book Kalman and Bayesian Filters in Python
85+
Simple example of a linear order 1 kinematic filter in 2D. There is no
86+
need to use a UKF for this example, but it is easy to read.
87+
88+
>>> def fx(x, dt):
89+
>>> # state transition function - predict next state based
90+
>>> # on constant velocity model x = vt + x_0
91+
>>> F = np.array([[1, dt, 0, 0],
92+
>>> [0, 1, 0, 0],
93+
>>> [0, 0, 1, dt],
94+
>>> [0, 0, 0, 1]], dtype=float)
95+
>>> return np.dot(F, x)
96+
>>>
97+
>>> def hx(x):
98+
>>> # measurement function - convert state into a measurement
99+
>>> # where measurements are [x_pos, y_pos]
100+
>>> return np.array([x[0], x[2]])
101+
>>>
102+
>>> dt = 0.1
103+
>>> # create sigma points to use in the filter. This is standard for Gaussian processes
104+
>>> points = MerweScaledSigmaPoints(4, alpha=.1, beta=2., kappa=-1)
105+
>>>
106+
>>> kf = UnscentedKalmanFilter(dim_x=4, dim_z=2, dt=dt, fx=fx, hx=hx, points=points)
107+
>>> kf.x = np.array([-1., 1., -1., 1]) # initial state
108+
>>> kf.P *= 0.2 # initial uncertainty
109+
>>> z_std = 0.1
110+
>>> kf.R = np.diag([z_std**2, z_std**2]) # 1 standard
111+
>>> kf.Q = Q_discrete_white_noise(dim=2, dt=dt, var=0.01**2, block_size=2)
112+
>>>
113+
>>> zs = [[i+randn()*z_std, i+randn()*z_std] for i in range(50)] # measurements
114+
>>> for z in zs:
115+
>>> kf.predict()
116+
>>> kf.update(z)
117+
>>> print(kf.x, 'log-likelihood', kf.log_likelihood)
118+
119+
For in depth explanations see my book Kalman and Bayesian Filters in Python
83120
https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python
84121
122+
Also see the filterpy/kalman/tests subdirectory for test code that
123+
may be illuminating.
85124
86125
References
87126
----------
@@ -144,7 +183,7 @@ def __init__(self, dim_x, dim_z, dt, hx, fx, points,
144183
parameterization. See either of those for the required
145184
signature of this class if you want to implement your own.
146185
147-
sqrt_fn : callable(ndarray), default = scipy.linalg.cholesky
186+
sqrt_fn : callable(ndarray), default=None (implies scipy.linalg.cholesky)
148187
Defines how we compute the square root of a matrix, which has
149188
no unique answer. Cholesky is the default choice due to its
150189
speed. Typically your alternative choice will be
@@ -158,7 +197,7 @@ def __init__(self, dim_x, dim_z, dt, hx, fx, points,
158197
If your method returns a triangular matrix it must be upper
159198
triangular. Do not use numpy.linalg.cholesky - for historical
160199
reasons it returns a lower triangular matrix. The SciPy version
161-
does the right thing.
200+
does the right thing as far as this class is concerned.
162201
163202
x_mean_fn : callable (sigma_points, weights), optional
164203
Function that computes the mean of the provided sigma points

0 commit comments

Comments
 (0)