Skip to content

Commit 3bf0f85

Browse files
committed
add fast_slam
1 parent 0bd52c3 commit 3bf0f85

File tree

1 file changed

+62
-4
lines changed

1 file changed

+62
-4
lines changed

SLAM/FastSLAM/fast_slam.py

Lines changed: 62 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -25,12 +25,65 @@
2525
STATE_SIZE = 3 # State size [x,y,yaw]
2626
LM_SIZE = 2 # LM srate size [x,y]
2727

28+
N_PARTICLE = 100 # number of particle
29+
2830
show_animation = True
2931

3032

31-
def fast_slam(xEst, PEst, u, z):
33+
class Particle:
34+
35+
def __init__(self):
36+
self.w = 1.0 / N_PARTICLE
37+
self.x = 0.0
38+
self.y = 0.0
39+
self.yaw = 0.0
40+
41+
42+
def calc_final_state(particles):
43+
44+
xEst = np.zeros((STATE_SIZE, 1))
45+
46+
for i in range(N_PARTICLE):
47+
xEst[0, 0] += particles[i].w * particles[i].x
48+
xEst[1, 0] += particles[i].w * particles[i].y
49+
xEst[2, 0] += particles[i].w * particles[i].yaw
50+
51+
xEst[2, 0] = pi_2_pi(xEst[2, 0])
52+
53+
return xEst
54+
55+
56+
def predict_particles(particles, u):
57+
58+
for i in range(N_PARTICLE):
59+
px = np.zeros((STATE_SIZE, 1))
60+
px[0, 0] = particles[i].x
61+
px[1, 0] = particles[i].y
62+
px[2, 0] = particles[i].yaw
63+
ud = u + np.matrix(np.random.randn(1, 2)) * Rsim # add noise
64+
px = motion_model(px, ud)
65+
particles[i].x = px[0, 0]
66+
particles[i].y = px[1, 0]
67+
particles[i].yaw = px[2, 0]
3268

33-
xEst[2] = pi_2_pi(xEst[2])
69+
return particles
70+
71+
72+
def update_with_observation(particle, z):
73+
74+
return particle
75+
76+
77+
def fast_slam(particles, PEst, u, z):
78+
79+
# Predict
80+
particles = predict_particles(particles, u)
81+
82+
# Observation
83+
for i in range(N_PARTICLE):
84+
particles[i] = update_with_observation(particles[i], z)
85+
86+
xEst = calc_final_state(particles)
3487

3588
return xEst, PEst
3689

@@ -163,13 +216,15 @@ def main():
163216
hxTrue = xTrue
164217
hxDR = xTrue
165218

219+
particles = [Particle() for i in range(N_PARTICLE)]
220+
166221
while SIM_TIME >= time:
167222
time += DT
168223
u = calc_input()
169224

170225
xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID)
171226

172-
xEst, PEst = fast_slam(xEst, PEst, ud, z)
227+
xEst, PEst = fast_slam(particles, PEst, ud, z)
173228

174229
x_state = xEst[0:STATE_SIZE]
175230

@@ -182,7 +237,10 @@ def main():
182237
plt.cla()
183238

184239
plt.plot(RFID[:, 0], RFID[:, 1], "*k")
185-
plt.plot(xEst[0], xEst[1], ".r")
240+
plt.plot(xEst[0], xEst[1], "xr")
241+
242+
for i in range(N_PARTICLE):
243+
plt.plot(particles[i].x, particles[i].y, ".r")
186244

187245
# plot landmark
188246
for i in range(calc_n_LM(xEst)):

0 commit comments

Comments
 (0)