Skip to content

Commit 91d6f0e

Browse files
committed
remove matrix to array
1 parent 44231dc commit 91d6f0e

File tree

1 file changed

+61
-67
lines changed

1 file changed

+61
-67
lines changed

SLAM/FastSLAM1/fast_slam1.py

Lines changed: 61 additions & 67 deletions
Original file line numberDiff line numberDiff line change
@@ -40,9 +40,9 @@ def __init__(self, N_LM):
4040
self.y = 0.0
4141
self.yaw = 0.0
4242
# landmark x-y positions
43-
self.lm = np.matrix(np.zeros((N_LM, LM_SIZE)))
43+
self.lm = np.zeros((N_LM, LM_SIZE))
4444
# landmark position covariance
45-
self.lmP = np.matrix(np.zeros((N_LM * LM_SIZE, LM_SIZE)))
45+
self.lmP = np.zeros((N_LM * LM_SIZE, LM_SIZE))
4646

4747

4848
def fast_slam1(particles, u, z):
@@ -96,7 +96,7 @@ def predict_particles(particles, u):
9696
px[0, 0] = particles[i].x
9797
px[1, 0] = particles[i].y
9898
px[2, 0] = particles[i].yaw
99-
ud = u + (np.matrix(np.random.randn(1, 2)) * R).T # add noise
99+
ud = u + (np.random.randn(1, 2) @ R).T # add noise
100100
px = motion_model(px, ud)
101101
particles[i].x = px[0, 0]
102102
particles[i].y = px[1, 0]
@@ -107,9 +107,9 @@ def predict_particles(particles, u):
107107

108108
def add_new_lm(particle, z, Q):
109109

110-
r = z[0, 0]
111-
b = z[0, 1]
112-
lm_id = int(z[0, 2])
110+
r = z[0]
111+
b = z[1]
112+
lm_id = int(z[2])
113113

114114
s = math.sin(pi_2_pi(particle.yaw + b))
115115
c = math.cos(pi_2_pi(particle.yaw + b))
@@ -118,10 +118,10 @@ def add_new_lm(particle, z, Q):
118118
particle.lm[lm_id, 1] = particle.y + r * s
119119

120120
# covariance
121-
Gz = np.matrix([[c, -r * s],
122-
[s, r * c]])
121+
Gz = np.array([[c, -r * s],
122+
[s, r * c]])
123123

124-
particle.lmP[2 * lm_id:2 * lm_id + 2] = Gz * Q * Gz.T
124+
particle.lmP[2 * lm_id:2 * lm_id + 2] = Gz @ Q @ Gz.T
125125

126126
return particle
127127

@@ -132,44 +132,44 @@ def compute_jacobians(particle, xf, Pf, Q):
132132
d2 = dx**2 + dy**2
133133
d = math.sqrt(d2)
134134

135-
zp = np.matrix([[d, pi_2_pi(math.atan2(dy, dx) - particle.yaw)]]).T
135+
zp = np.array([[d, pi_2_pi(math.atan2(dy, dx) - particle.yaw)]]).T
136136

137-
Hv = np.matrix([[-dx / d, -dy / d, 0.0],
138-
[dy / d2, -dx / d2, -1.0]])
137+
Hv = np.array([[-dx / d, -dy / d, 0.0],
138+
[dy / d2, -dx / d2, -1.0]])
139139

140-
Hf = np.matrix([[dx / d, dy / d],
141-
[-dy / d2, dx / d2]])
140+
Hf = np.array([[dx / d, dy / d],
141+
[-dy / d2, dx / d2]])
142142

143-
Sf = Hf * Pf * Hf.T + Q
143+
Sf = Hf @ Pf @ Hf.T + Q
144144

145145
return zp, Hv, Hf, Sf
146146

147147

148148
def update_KF_with_cholesky(xf, Pf, v, Q, Hf):
149-
PHt = Pf * Hf.T
150-
S = Hf * PHt + Q
149+
PHt = Pf @ Hf.T
150+
S = Hf @ PHt + Q
151151

152152
S = (S + S.T) * 0.5
153153
SChol = np.linalg.cholesky(S).T
154154
SCholInv = np.linalg.inv(SChol)
155-
W1 = PHt * SCholInv
156-
W = W1 * SCholInv.T
155+
W1 = PHt @ SCholInv
156+
W = W1 @ SCholInv.T
157157

158-
x = xf + W * v
159-
P = Pf - W1 * W1.T
158+
x = xf + W @ v
159+
P = Pf - W1 @ W1.T
160160

161161
return x, P
162162

163163

164164
def update_landmark(particle, z, Q):
165165

166-
lm_id = int(z[0, 2])
167-
xf = np.matrix(particle.lm[lm_id, :]).T
168-
Pf = np.matrix(particle.lmP[2 * lm_id:2 * lm_id + 2, :])
166+
lm_id = int(z[2])
167+
xf = np.array(particle.lm[lm_id, :]).reshape(2, 1)
168+
Pf = np.array(particle.lmP[2 * lm_id:2 * lm_id + 2, :])
169169

170170
zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q)
171171

172-
dz = z[0, 0: 2].T - zp
172+
dz = z[0:2].reshape(2, 1) - zp
173173
dz[1, 0] = pi_2_pi(dz[1, 0])
174174

175175
xf, Pf = update_KF_with_cholesky(xf, Pf, dz, Q, Hf)
@@ -181,13 +181,12 @@ def update_landmark(particle, z, Q):
181181

182182

183183
def compute_weight(particle, z, Q):
184-
185-
lm_id = int(z[0, 2])
186-
xf = np.matrix(particle.lm[lm_id, :]).T
187-
Pf = np.matrix(particle.lmP[2 * lm_id:2 * lm_id + 2])
184+
lm_id = int(z[2])
185+
xf = np.array(particle.lm[lm_id, :]).reshape(2, 1)
186+
Pf = np.array(particle.lmP[2 * lm_id:2 * lm_id + 2])
188187
zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q)
189188

190-
dx = z[0, 0: 2].T - zp
189+
dx = z[0:2].reshape(2, 1) - zp
191190
dx[1, 0] = pi_2_pi(dx[1, 0])
192191

193192
try:
@@ -196,7 +195,7 @@ def compute_weight(particle, z, Q):
196195
print("singuler")
197196
return 1.0
198197

199-
num = math.exp(-0.5 * dx.T * invS * dx)
198+
num = math.exp(-0.5 * dx.T @ invS @ dx)
200199
den = 2.0 * math.pi * math.sqrt(np.linalg.det(Sf))
201200

202201
w = num / den
@@ -206,19 +205,19 @@ def compute_weight(particle, z, Q):
206205

207206
def update_with_observation(particles, z):
208207

209-
for iz in range(len(z[:, 0])):
208+
for iz in range(len(z[0, :])):
210209

211-
lmid = int(z[iz, 2])
210+
lmid = int(z[2, iz])
212211

213212
for ip in range(N_PARTICLE):
214213
# new landmark
215214
if abs(particles[ip].lm[lmid, 0]) <= 0.01:
216-
particles[ip] = add_new_lm(particles[ip], z[iz, :], Q)
215+
particles[ip] = add_new_lm(particles[ip], z[:, iz], Q)
217216
# known landmark
218217
else:
219-
w = compute_weight(particles[ip], z[iz, :], Q)
218+
w = compute_weight(particles[ip], z[:, iz], Q)
220219
particles[ip].w *= w
221-
particles[ip] = update_landmark(particles[ip], z[iz, :], Q)
220+
particles[ip] = update_landmark(particles[ip], z[:, iz], Q)
222221

223222
return particles
224223

@@ -234,20 +233,20 @@ def resampling(particles):
234233
for i in range(N_PARTICLE):
235234
pw.append(particles[i].w)
236235

237-
pw = np.matrix(pw)
236+
pw = np.array(pw)
238237

239-
Neff = 1.0 / (pw * pw.T)[0, 0] # Effective particle number
240-
# print(Neff)
238+
Neff = 1.0 / (pw @ pw.T) # Effective particle number
239+
# print(Neff)
241240

242241
if Neff < NTH: # resampling
243242
wcum = np.cumsum(pw)
244243
base = np.cumsum(pw * 0.0 + 1 / N_PARTICLE) - 1 / N_PARTICLE
245-
resampleid = base + np.random.rand(base.shape[1]) / N_PARTICLE
244+
resampleid = base + np.random.rand(base.shape[0]) / N_PARTICLE
246245

247246
inds = []
248247
ind = 0
249248
for ip in range(N_PARTICLE):
250-
while ((ind < wcum.shape[1] - 1) and (resampleid[0, ip] > wcum[0, ind])):
249+
while ((ind < wcum.shape[0] - 1) and (resampleid[ip] > wcum[ind])):
251250
ind += 1
252251
inds.append(ind)
253252

@@ -265,25 +264,25 @@ def resampling(particles):
265264

266265
def calc_input(time):
267266

268-
if time <= 3.0:
267+
if time <= 3.0: # wait at first
269268
v = 0.0
270269
yawrate = 0.0
271270
else:
272271
v = 1.0 # [m/s]
273272
yawrate = 0.1 # [rad/s]
274273

275-
u = np.matrix([v, yawrate]).T
274+
u = np.array([v, yawrate]).reshape(2, 1)
276275

277276
return u
278277

279278

280279
def observation(xTrue, xd, u, RFID):
281280

281+
# calc true state
282282
xTrue = motion_model(xTrue, u)
283283

284-
# add noise to gps x-y
285-
z = np.matrix(np.zeros((0, 3)))
286-
284+
# add noise to range observation
285+
z = np.zeros((3, 0))
287286
for i in range(len(RFID[:, 0])):
288287

289288
dx = RFID[i, 0] - xTrue[0, 0]
@@ -293,13 +292,13 @@ def observation(xTrue, xd, u, RFID):
293292
if d <= MAX_RANGE:
294293
dn = d + np.random.randn() * Qsim[0, 0] # add noise
295294
anglen = angle + np.random.randn() * Qsim[1, 1] # add noise
296-
zi = np.matrix([dn, pi_2_pi(anglen), i])
297-
z = np.vstack((z, zi))
295+
zi = np.array([dn, pi_2_pi(anglen), i]).reshape(3, 1)
296+
z = np.hstack((z, zi))
298297

299298
# add noise to input
300299
ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0]
301300
ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1] + OFFSET_YAWRATE_NOISE
302-
ud = np.matrix([ud1, ud2]).T
301+
ud = np.array([ud1, ud2]).reshape(2, 1)
303302

304303
xd = motion_model(xd, ud)
305304

@@ -308,15 +307,15 @@ def observation(xTrue, xd, u, RFID):
308307

309308
def motion_model(x, u):
310309

311-
F = np.matrix([[1.0, 0, 0],
312-
[0, 1.0, 0],
313-
[0, 0, 1.0]])
310+
F = np.array([[1.0, 0, 0],
311+
[0, 1.0, 0],
312+
[0, 0, 1.0]])
314313

315-
B = np.matrix([[DT * math.cos(x[2, 0]), 0],
316-
[DT * math.sin(x[2, 0]), 0],
317-
[0.0, DT]])
314+
B = np.array([[DT * math.cos(x[2, 0]), 0],
315+
[DT * math.sin(x[2, 0]), 0],
316+
[0.0, DT]])
318317

319-
x = F * x + B * u
318+
x = F @ x + B @ u
320319

321320
x[2, 0] = pi_2_pi(x[2, 0])
322321

@@ -345,10 +344,9 @@ def main():
345344
N_LM = RFID.shape[0]
346345

347346
# State Vector [x y yaw v]'
348-
xEst = np.matrix(np.zeros((STATE_SIZE, 1)))
349-
xTrue = np.matrix(np.zeros((STATE_SIZE, 1)))
350-
351-
xDR = np.matrix(np.zeros((STATE_SIZE, 1))) # Dead reckoning
347+
xEst = np.zeros((STATE_SIZE, 1)) # SLAM estimation
348+
xTrue = np.zeros((STATE_SIZE, 1)) # True state
349+
xDR = np.zeros((STATE_SIZE, 1)) # Dead reckoning
352350

353351
# history
354352
hxEst = xEst
@@ -382,13 +380,9 @@ def main():
382380
plt.plot(particles[i].x, particles[i].y, ".r")
383381
plt.plot(particles[i].lm[:, 0], particles[i].lm[:, 1], "xb")
384382

385-
plt.plot(np.array(hxTrue[0, :]).flatten(),
386-
np.array(hxTrue[1, :]).flatten(), "-b")
387-
plt.plot(np.array(hxDR[0, :]).flatten(),
388-
np.array(hxDR[1, :]).flatten(), "-k")
389-
plt.plot(np.array(hxEst[0, :]).flatten(),
390-
np.array(hxEst[1, :]).flatten(), "-r")
391-
383+
plt.plot(hxTrue[0, :], hxTrue[1, :], "-b")
384+
plt.plot(hxDR[0, :], hxDR[1, :], "-k")
385+
plt.plot(hxEst[0, :], hxEst[1, :], "-r")
392386
plt.plot(xEst[0], xEst[1], "xk")
393387
plt.axis("equal")
394388
plt.grid(True)

0 commit comments

Comments
 (0)