Skip to content

Commit dee0fe7

Browse files
committed
2 parents 23c7356 + 87a5517 commit dee0fe7

File tree

7 files changed

+206
-245
lines changed

7 files changed

+206
-245
lines changed

Localization/ensemble_kalman_filter/ensemble_kalman_filter.py

Lines changed: 45 additions & 50 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,3 @@
1-
21
"""
32
43
Ensemble Kalman Filter(EnKF) localization sample
@@ -10,13 +9,14 @@
109
1110
"""
1211

13-
import numpy as np
1412
import math
13+
1514
import matplotlib.pyplot as plt
15+
import numpy as np
1616

1717
# Simulation parameter
18-
Qsim = np.diag([0.2, np.deg2rad(1.0)])**2
19-
Rsim = np.diag([1.0, np.deg2rad(30.0)])**2
18+
Q_sim = np.diag([0.2, np.deg2rad(1.0)]) ** 2
19+
R_sim = np.diag([1.0, np.deg2rad(30.0)]) ** 2
2020

2121
DT = 0.1 # time tick [s]
2222
SIM_TIME = 50.0 # simulation time [s]
@@ -30,13 +30,12 @@
3030

3131
def calc_input():
3232
v = 1.0 # [m/s]
33-
yawrate = 0.1 # [rad/s]
34-
u = np.array([[v, yawrate]]).T
33+
yaw_rate = 0.1 # [rad/s]
34+
u = np.array([[v, yaw_rate]]).T
3535
return u
3636

3737

3838
def observation(xTrue, xd, u, RFID):
39-
4039
xTrue = motion_model(xTrue, u)
4140

4241
z = np.zeros((0, 4))
@@ -45,18 +44,18 @@ def observation(xTrue, xd, u, RFID):
4544

4645
dx = RFID[i, 0] - xTrue[0, 0]
4746
dy = RFID[i, 1] - xTrue[1, 0]
48-
d = math.sqrt(dx**2 + dy**2)
47+
d = math.sqrt(dx ** 2 + dy ** 2)
4948
angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0])
5049
if d <= MAX_RANGE:
51-
dn = d + np.random.randn() * Qsim[0, 0] # add noise
52-
anglen = angle + np.random.randn() * Qsim[1, 1] # add noise
50+
dn = d + np.random.randn() * Q_sim[0, 0] ** 0.5 # add noise
51+
anglen = angle + np.random.randn() * Q_sim[1, 1] ** 0.5 # add noise
5352
zi = np.array([dn, anglen, RFID[i, 0], RFID[i, 1]])
5453
z = np.vstack((z, zi))
5554

5655
# add noise to input
5756
ud = np.array([[
58-
u[0, 0] + np.random.randn() * Rsim[0, 0],
59-
u[1, 0] + np.random.randn() * Rsim[1, 1]]]).T
57+
u[0, 0] + np.random.randn() * R_sim[0, 0] ** 0.5,
58+
u[1, 0] + np.random.randn() * R_sim[1, 1] ** 0.5]]).T
6059

6160
xd = motion_model(xd, ud)
6261
return xTrue, z, xd, ud
@@ -77,15 +76,13 @@ def motion_model(x, u):
7776
return x
7877

7978

80-
def calc_LM_Pos(x, landmarks):
81-
landmarks_pos = np.zeros((2*landmarks.shape[0], 1))
79+
def observe_landmark_position(x, landmarks):
80+
landmarks_pos = np.zeros((2 * landmarks.shape[0], 1))
8281
for (i, lm) in enumerate(landmarks):
83-
landmarks_pos[2*i] = x[0, 0] + lm[0] * \
84-
math.cos(x[2, 0] + lm[1]) + np.random.randn() * \
85-
Qsim[0, 0]/np.sqrt(2)
86-
landmarks_pos[2*i+1] = x[1, 0] + lm[0] * \
87-
math.sin(x[2, 0] + lm[1]) + np.random.randn() * \
88-
Qsim[0, 0]/np.sqrt(2)
82+
landmarks_pos[2 * i] = x[0, 0] + lm[0] * math.cos(x[2, 0] + lm[1]) + np.random.randn() * Q_sim[
83+
0, 0] ** 0.5 / np.sqrt(2)
84+
landmarks_pos[2 * i + 1] = x[1, 0] + lm[0] * math.sin(x[2, 0] + lm[1]) + np.random.randn() * Q_sim[
85+
0, 0] ** 0.5 / np.sqrt(2)
8986
return landmarks_pos
9087

9188

@@ -95,25 +92,26 @@ def calc_covariance(xEst, px):
9592
for i in range(px.shape[1]):
9693
dx = (px[:, i] - xEst)[0:3]
9794
cov += dx.dot(dx.T)
95+
cov /= NP
9896

9997
return cov
10098

10199

102-
def enkf_localization(px, xEst, PEst, z, u):
100+
def enkf_localization(px, z, u):
103101
"""
104102
Localization with Ensemble Kalman filter
105103
"""
106-
pz = np.zeros((z.shape[0]*2, NP)) # Particle store of z
104+
pz = np.zeros((z.shape[0] * 2, NP)) # Particle store of z
107105
for ip in range(NP):
108106
x = np.array([px[:, ip]]).T
109107

110108
# Predict with random input sampling
111-
ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0]
112-
ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1]
109+
ud1 = u[0, 0] + np.random.randn() * R_sim[0, 0] ** 0.5
110+
ud2 = u[1, 0] + np.random.randn() * R_sim[1, 1] ** 0.5
113111
ud = np.array([[ud1, ud2]]).T
114112
x = motion_model(x, ud)
115113
px[:, ip] = x[:, 0]
116-
z_pos = calc_LM_Pos(x, z)
114+
z_pos = observe_landmark_position(x, z)
117115
pz[:, ip] = z_pos[:, 0]
118116

119117
x_ave = np.mean(px, axis=1)
@@ -122,12 +120,12 @@ def enkf_localization(px, xEst, PEst, z, u):
122120
z_ave = np.mean(pz, axis=1)
123121
z_dif = pz - np.tile(z_ave, (NP, 1)).T
124122

125-
U = 1/(NP-1) * x_dif @ z_dif.T
126-
V = 1/(NP-1) * z_dif @ z_dif.T
123+
U = 1 / (NP - 1) * x_dif @ z_dif.T
124+
V = 1 / (NP - 1) * z_dif @ z_dif.T
127125

128126
K = U @ np.linalg.inv(V) # Kalman Gain
129127

130-
z_lm_pos = z[:, [2, 3]].reshape(-1,)
128+
z_lm_pos = z[:, [2, 3]].reshape(-1, )
131129

132130
px_hat = px + K @ (np.tile(z_lm_pos, (NP, 1)).T - pz)
133131

@@ -139,32 +137,32 @@ def enkf_localization(px, xEst, PEst, z, u):
139137

140138
def plot_covariance_ellipse(xEst, PEst): # pragma: no cover
141139
Pxy = PEst[0:2, 0:2]
142-
eigval, eigvec = np.linalg.eig(Pxy)
140+
eig_val, eig_vec = np.linalg.eig(Pxy)
143141

144-
if eigval[0] >= eigval[1]:
145-
bigind = 0
146-
smallind = 1
142+
if eig_val[0] >= eig_val[1]:
143+
big_ind = 0
144+
small_ind = 1
147145
else:
148-
bigind = 1
149-
smallind = 0
146+
big_ind = 1
147+
small_ind = 0
150148

151149
t = np.arange(0, 2 * math.pi + 0.1, 0.1)
152150

153-
# eigval[bigind] or eiqval[smallind] were occassionally negative numbers extremely
151+
# eig_val[big_ind] or eiq_val[small_ind] were occasionally negative numbers extremely
154152
# close to 0 (~10^-20), catch these cases and set the respective variable to 0
155153
try:
156-
a = math.sqrt(eigval[bigind])
154+
a = math.sqrt(eig_val[big_ind])
157155
except ValueError:
158156
a = 0
159157

160158
try:
161-
b = math.sqrt(eigval[smallind])
159+
b = math.sqrt(eig_val[small_ind])
162160
except ValueError:
163161
b = 0
164162

165163
x = [a * math.cos(it) for it in t]
166164
y = [b * math.sin(it) for it in t]
167-
angle = math.atan2(eigvec[bigind, 1], eigvec[bigind, 0])
165+
angle = math.atan2(eig_vec[big_ind, 1], eig_vec[big_ind, 0])
168166
R = np.array([[math.cos(angle), math.sin(angle)],
169167
[-math.sin(angle), math.cos(angle)]])
170168
fx = R.dot(np.array([[x, y]]))
@@ -182,17 +180,15 @@ def main():
182180

183181
time = 0.0
184182

185-
# RFID positions [x, y]
186-
RFID = np.array([[10.0, 0.0],
187-
[10.0, 10.0],
188-
[0.0, 15.0],
189-
[-5.0, 20.0]])
183+
# RF_ID positions [x, y]
184+
RF_ID = np.array([[10.0, 0.0],
185+
[10.0, 10.0],
186+
[0.0, 15.0],
187+
[-5.0, 20.0]])
190188

191189
# State Vector [x y yaw v]'
192190
xEst = np.zeros((4, 1))
193191
xTrue = np.zeros((4, 1))
194-
PEst = np.eye(4)
195-
196192
px = np.zeros((4, NP)) # Particle store of x
197193

198194
xDR = np.zeros((4, 1)) # Dead reckoning
@@ -206,9 +202,9 @@ def main():
206202
time += DT
207203
u = calc_input()
208204

209-
xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID)
205+
xTrue, z, xDR, ud = observation(xTrue, xDR, u, RF_ID)
210206

211-
xEst, PEst, px = enkf_localization(px, xEst, PEst, z, ud)
207+
xEst, PEst, px = enkf_localization(px, z, ud)
212208

213209
# store data history
214210
hxEst = np.hstack((hxEst, xEst))
@@ -220,20 +216,19 @@ def main():
220216

221217
for i in range(len(z[:, 0])):
222218
plt.plot([xTrue[0, 0], z[i, 2]], [xTrue[1, 0], z[i, 3]], "-k")
223-
plt.plot(RFID[:, 0], RFID[:, 1], "*k")
219+
plt.plot(RF_ID[:, 0], RF_ID[:, 1], "*k")
224220
plt.plot(px[0, :], px[1, :], ".r")
225221
plt.plot(np.array(hxTrue[0, :]).flatten(),
226222
np.array(hxTrue[1, :]).flatten(), "-b")
227223
plt.plot(np.array(hxDR[0, :]).flatten(),
228224
np.array(hxDR[1, :]).flatten(), "-k")
229225
plt.plot(np.array(hxEst[0, :]).flatten(),
230226
np.array(hxEst[1, :]).flatten(), "-r")
231-
#plot_covariance_ellipse(xEst, PEst)
227+
# plot_covariance_ellipse(xEst, PEst)
232228
plt.axis("equal")
233229
plt.grid(True)
234230
plt.pause(0.001)
235231

236232

237233
if __name__ == '__main__':
238234
main()
239-

Localization/extended_kalman_filter/extended_kalman_filter.py

Lines changed: 22 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -7,21 +7,22 @@
77
"""
88

99
import math
10-
import numpy as np
10+
1111
import matplotlib.pyplot as plt
12+
import numpy as np
1213

1314
# Covariance for EKF simulation
1415
Q = np.diag([
15-
0.1, # variance of location on x-axis
16-
0.1, # variance of location on y-axis
17-
np.deg2rad(1.0), # variance of yaw angle
18-
1.0 # variance of velocity
19-
])**2 # predict state covariance
20-
R = np.diag([1.0, 1.0])**2 # Observation x,y position covariance
16+
0.1, # variance of location on x-axis
17+
0.1, # variance of location on y-axis
18+
np.deg2rad(1.0), # variance of yaw angle
19+
1.0 # variance of velocity
20+
]) ** 2 # predict state covariance
21+
R = np.diag([1.0, 1.0]) ** 2 # Observation x,y position covariance
2122

2223
# Simulation parameter
23-
INPUT_NOISE = np.diag([1.0, np.deg2rad(30.0)])**2
24-
GPS_NOISE = np.diag([0.5, 0.5])**2
24+
INPUT_NOISE = np.diag([1.0, np.deg2rad(30.0)]) ** 2
25+
GPS_NOISE = np.diag([0.5, 0.5]) ** 2
2526

2627
DT = 0.1 # time tick [s]
2728
SIM_TIME = 50.0 # simulation time [s]
@@ -37,7 +38,6 @@ def calc_input():
3738

3839

3940
def observation(xTrue, xd, u):
40-
4141
xTrue = motion_model(xTrue, u)
4242

4343
# add noise to gps x-y
@@ -52,7 +52,6 @@ def observation(xTrue, xd, u):
5252

5353

5454
def motion_model(x, u):
55-
5655
F = np.array([[1.0, 0, 0, 0],
5756
[0, 1.0, 0, 0],
5857
[0, 0, 1.0, 0],
@@ -79,7 +78,7 @@ def observation_model(x):
7978
return z
8079

8180

82-
def jacobF(x, u):
81+
def jacob_f(x, u):
8382
"""
8483
Jacobian of Motion Model
8584
@@ -105,7 +104,7 @@ def jacobF(x, u):
105104
return jF
106105

107106

108-
def jacobH(x):
107+
def jacob_h():
109108
# Jacobian of Observation Model
110109
jH = np.array([
111110
[1, 0, 0, 0],
@@ -116,20 +115,19 @@ def jacobH(x):
116115

117116

118117
def ekf_estimation(xEst, PEst, z, u):
119-
120118
# Predict
121119
xPred = motion_model(xEst, u)
122-
jF = jacobF(xPred, u)
123-
PPred = jF@PEst@jF.T + Q
120+
jF = jacob_f(xPred, u)
121+
PPred = jF @ PEst @ jF.T + Q
124122

125123
# Update
126-
jH = jacobH(xPred)
124+
jH = jacob_h()
127125
zPred = observation_model(xPred)
128126
y = z - zPred
129-
S = jH@PPred@jH.T + R
130-
K = PPred@jH.T@np.linalg.inv(S)
131-
xEst = xPred + K@y
132-
PEst = (np.eye(len(xEst)) - K@jH)@PPred
127+
S = jH @ PPred @ jH.T + R
128+
K = PPred @ jH.T @ np.linalg.inv(S)
129+
xEst = xPred + K @ y
130+
PEst = (np.eye(len(xEst)) - K @ jH) @ PPred
133131

134132
return xEst, PEst
135133

@@ -151,9 +149,9 @@ def plot_covariance_ellipse(xEst, PEst): # pragma: no cover
151149
x = [a * math.cos(it) for it in t]
152150
y = [b * math.sin(it) for it in t]
153151
angle = math.atan2(eigvec[bigind, 1], eigvec[bigind, 0])
154-
R = np.array([[math.cos(angle), math.sin(angle)],
155-
[-math.sin(angle), math.cos(angle)]])
156-
fx = R@(np.array([x, y]))
152+
rot = np.array([[math.cos(angle), math.sin(angle)],
153+
[-math.sin(angle), math.cos(angle)]])
154+
fx = rot @ (np.array([x, y]))
157155
px = np.array(fx[0, :] + xEst[0, 0]).flatten()
158156
py = np.array(fx[1, :] + xEst[1, 0]).flatten()
159157
plt.plot(px, py, "--r")

0 commit comments

Comments
 (0)