Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Download
96131 views
1
# -*- coding: utf-8 -*-
2
3
"""Copyright 2015 Roger R Labbe Jr.
4
5
FilterPy library.
6
http://github.com/rlabbe/filterpy
7
8
Documentation at:
9
https://filterpy.readthedocs.org
10
11
Supporting book at:
12
https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python
13
14
This is licensed under an MIT license. See the readme.MD file
15
for more information.
16
"""
17
18
from __future__ import (absolute_import, division, print_function,
19
unicode_literals)
20
import numpy as np
21
import scipy.linalg as linalg
22
from numpy import dot, zeros, eye
23
from filterpy.common import setter, setter_1d, setter_scalar, dot3
24
25
26
class ExtendedKalmanFilter(object):
27
28
def __init__(self, dim_x, dim_z, dim_u=0):
29
""" Extended Kalman filter. You are responsible for setting the
30
various state variables to reasonable values; the defaults below will
31
not give you a functional filter.
32
33
**Parameters**
34
35
dim_x : int
36
Number of state variables for the Kalman filter. For example, if
37
you are tracking the position and velocity of an object in two
38
dimensions, dim_x would be 4.
39
40
This is used to set the default size of P, Q, and u
41
42
dim_z : int
43
Number of of measurement inputs. For example, if the sensor
44
provides you with position in (x,y), dim_z would be 2.
45
"""
46
47
self.dim_x = dim_x
48
self.dim_z = dim_z
49
50
self._x = zeros((dim_x,1)) # state
51
self._P = eye(dim_x) # uncertainty covariance
52
self._B = 0 # control transition matrix
53
self._F = 0 # state transition matrix
54
self._R = eye(dim_z) # state uncertainty
55
self._Q = eye(dim_x) # process uncertainty
56
self._y = zeros((dim_z, 1))
57
58
# identity matrix. Do not alter this.
59
self._I = np.eye(dim_x)
60
61
62
def predict_update(self, z, HJacobian, Hx, args=(), hx_args=(), u=0):
63
""" Performs the predict/update innovation of the extended Kalman
64
filter.
65
66
**Parameters**
67
68
z : np.array
69
measurement for this step.
70
If `None`, only predict step is perfomed.
71
72
HJacobian : function
73
function which computes the Jacobian of the H matrix (measurement
74
function). Takes state variable (self.x) as input, along with the
75
optional arguments in args, and returns H.
76
77
Hx : function
78
function which takes as input the state variable (self.x) along
79
with the optional arguments in hx_args, and returns the measurement
80
that would correspond to that state.
81
82
args : tuple, optional, default (,)
83
arguments to be passed into HJacobian after the required state
84
variable.
85
86
hx_args : tuple, optional, default (,)
87
arguments to be passed into HJacobian after the required state
88
variable.
89
90
u : np.array or scalar
91
optional control vector input to the filter.
92
"""
93
94
if not isinstance(args, tuple):
95
args = (args,)
96
97
if not isinstance(hx_args, tuple):
98
hx_args = (hx_args,)
99
100
if np.isscalar(z) and self.dim_z == 1:
101
z = np.asarray([z], float)
102
103
F = self._F
104
B = self._B
105
P = self._P
106
Q = self._Q
107
R = self._R
108
x = self._x
109
110
H = HJacobian(x, *args)
111
112
# predict step
113
x = dot(F, x) + dot(B, u)
114
P = dot3(F, P, F.T) + Q
115
116
# update step
117
S = dot3(H, P, H.T) + R
118
K = dot3(P, H.T, linalg.inv (S))
119
120
self._x = x + dot(K, (z - Hx(x, *hx_args)))
121
122
I_KH = self._I - dot(K, H)
123
self._P = dot3(I_KH, P, I_KH.T) + dot3(K, R, K.T)
124
125
126
def update(self, z, HJacobian, Hx, R=None, args=(), hx_args=(),
127
residual=np.subtract):
128
""" Performs the update innovation of the extended Kalman filter.
129
130
**Parameters**
131
132
z : np.array
133
measurement for this step.
134
If `None`, only predict step is perfomed.
135
136
HJacobian : function
137
function which computes the Jacobian of the H matrix (measurement
138
function). Takes state variable (self.x) as input, returns H.
139
140
Hx : function
141
function which takes as input the state variable (self.x) along
142
with the optional arguments in hx_args, and returns the measurement
143
that would correspond to that state.
144
145
R : np.array, scalar, or None
146
Optionally provide R to override the measurement noise for this
147
one call, otherwise self.R will be used.
148
149
args : tuple, optional, default (,)
150
arguments to be passed into HJacobian after the required state
151
variable. for robot localization you might need to pass in
152
information about the map and time of day, so you might have
153
`args=(map_data, time)`, where the signature of HCacobian will
154
be `def HJacobian(x, map, t)`
155
156
hx_args : tuple, optional, default (,)
157
arguments to be passed into Hx function after the required state
158
variable.
159
160
residual : function (z, z2), optional
161
Optional function that computes the residual (difference) between
162
the two measurement vectors. If you do not provide this, then the
163
built in minus operator will be used. You will normally want to use
164
the built in unless your residual computation is nonlinear (for
165
example, if they are angles)
166
"""
167
168
if not isinstance(args, tuple):
169
args = (args,)
170
171
if not isinstance(hx_args, tuple):
172
hx_args = (hx_args,)
173
174
P = self._P
175
if R is None:
176
R = self._R
177
elif np.isscalar(R):
178
R = eye(self.dim_z) * R
179
180
if np.isscalar(z) and self.dim_z == 1:
181
z = np.asarray([z], float)
182
183
x = self._x
184
185
H = HJacobian(x, *args)
186
187
S = dot3(H, P, H.T) + R
188
K = dot3(P, H.T, linalg.inv (S))
189
190
hx = Hx(x, *hx_args)
191
y = residual(z, hx)
192
self._x = x + dot(K, y)
193
194
I_KH = self._I - dot(K, H)
195
self._P = dot3(I_KH, P, I_KH.T) + dot3(K, R, K.T)
196
197
198
def predict_x(self, u=0):
199
""" predicts the next state of X. If you need to
200
compute the next state yourself, override this function. You would
201
need to do this, for example, if the usual Taylor expansion to
202
generate F is not providing accurate results for you. """
203
204
self._x = dot(self._F, self._x) + dot(self._B, u)
205
206
207
def predict(self, u=0):
208
""" Predict next position.
209
210
**Parameters**
211
212
u : np.array
213
Optional control vector. If non-zero, it is multiplied by B
214
to create the control input into the system.
215
"""
216
217
self.predict_x(u)
218
self._P = dot3(self._F, self._P, self._F.T) + self._Q
219
220
221
@property
222
def Q(self):
223
""" Process uncertainty"""
224
return self._Q
225
226
227
@Q.setter
228
def Q(self, value):
229
self._Q = setter_scalar(value, self.dim_x)
230
231
232
@property
233
def P(self):
234
""" covariance matrix"""
235
return self._P
236
237
238
@P.setter
239
def P(self, value):
240
self._P = setter_scalar(value, self.dim_x)
241
242
243
@property
244
def R(self):
245
""" measurement uncertainty"""
246
return self._R
247
248
249
@R.setter
250
def R(self, value):
251
self._R = setter_scalar(value, self.dim_z)
252
253
254
@property
255
def F(self):
256
return self._F
257
258
259
@F.setter
260
def F(self, value):
261
self._F = setter(value, self.dim_x, self.dim_x)
262
263
264
@property
265
def B(self):
266
return self._B
267
268
269
@B.setter
270
def B(self, value):
271
""" control transition matrix"""
272
self._B = setter(value, self.dim_x, self.dim_u)
273
274
275
@property
276
def x(self):
277
return self._x
278
279
@x.setter
280
def x(self, value):
281
self._x = setter_1d(value, self.dim_x)
282
283
@property
284
def K(self):
285
""" Kalman gain """
286
return self._K
287
288
@property
289
def y(self):
290
""" measurement residual (innovation) """
291
return self._y
292
293
@property
294
def S(self):
295
""" system uncertainty in measurement space """
296
return self._S
297
298
299
300