2727
2828N_PARTICLE = 100 # number of particle
2929
30+ NTH = N_PARTICLE / 2.0 # Number of particle for re-sampling
31+
3032show_animation = True
3133
3234
@@ -52,8 +54,6 @@ def normalize_weight(particles):
5254
5355def calc_final_state (particles ):
5456
55- particles = normalize_weight (particles )
56-
5757 xEst = np .zeros ((STATE_SIZE , 1 ))
5858
5959 for i in range (N_PARTICLE ):
@@ -102,9 +102,19 @@ def compute_weight(particle, z):
102102 lm_id = int (z [0 , 2 ])
103103
104104 lmxy = np .matrix (particle .lm [lm_id , :])
105- zxy = z [0 , 0 :2 ]
106- # print(lmxy)
107- # print(zxy)
105+
106+ # calc landmark xy
107+ r = z [0 , 0 ]
108+ b = z [0 , 1 ]
109+ lm_id = int (z [0 , 2 ])
110+
111+ s = math .sin (particle .yaw + b )
112+ c = math .cos (particle .yaw + b )
113+
114+ zxy = np .zeros ((1 , 2 ))
115+
116+ zxy [0 , 0 ] = particle .x + r * c
117+ zxy [0 , 1 ] = particle .y + r * s
108118
109119 dx = (lmxy - zxy ).T
110120 S = np .eye (2 )
@@ -136,6 +146,40 @@ def update_with_observation(particles, z):
136146 return particles
137147
138148
149+ def resampling (particles ):
150+ """
151+ low variance re-sampling
152+ """
153+
154+ pw = []
155+ for i in range (N_PARTICLE ):
156+ pw .append (particles [i ].w )
157+
158+ pw = np .matrix (pw )
159+
160+ Neff = 1.0 / (pw * pw .T )[0 , 0 ] # Effective particle number
161+
162+ if Neff < NTH : # resampling
163+ wcum = np .cumsum (pw )
164+ base = np .cumsum (pw * 0.0 + 1 / N_PARTICLE ) - 1 / N_PARTICLE
165+ resampleid = base + np .random .rand (base .shape [1 ]) / N_PARTICLE
166+
167+ inds = []
168+ ind = 0
169+ for ip in range (N_PARTICLE ):
170+ while resampleid [0 , ip ] > wcum [0 , ind ]:
171+ ind += 1
172+ inds .append (ind )
173+
174+ tparticles = particles [:]
175+ for i in range (len (inds )):
176+ particles [i ] = tparticles [inds [i ]]
177+
178+ particles = normalize_weight (particles )
179+
180+ return particles
181+
182+
139183def fast_slam (particles , PEst , u , z ):
140184
141185 # Predict
@@ -144,6 +188,10 @@ def fast_slam(particles, PEst, u, z):
144188 # Observation
145189 particles = update_with_observation (particles , z )
146190
191+ particles = normalize_weight (particles )
192+
193+ particles = resampling (particles )
194+
147195 xEst = calc_final_state (particles )
148196
149197 return xEst , PEst
@@ -222,28 +270,6 @@ def get_LM_Pos_from_state(x, ind):
222270 return lm
223271
224272
225- def search_correspond_LM_ID (xAug , PAug , zi ):
226- """
227- Landmark association with Nearest Neighbor
228- """
229-
230- nLM = calc_n_LM (xAug )
231-
232- mdist = []
233-
234- for i in range (nLM ):
235- # lm = get_LM_Pos_from_state(xAug, i)
236- # # y, S, H = calc_innovation(lm, xAug, PAug, zi, i)
237- # mdist.append(y.T * np.linalg.inv(S) * y)
238- pass
239-
240- mdist .append (M_DIST_TH ) # new landmark
241-
242- minid = mdist .index (min (mdist ))
243-
244- return minid
245-
246-
247273def pi_2_pi (angle ):
248274 while (angle > math .pi ):
249275 angle = angle - 2.0 * math .pi
@@ -299,7 +325,6 @@ def main():
299325 plt .cla ()
300326
301327 plt .plot (RFID [:, 0 ], RFID [:, 1 ], "*k" )
302- plt .plot (xEst [0 ], xEst [1 ], "xr" )
303328
304329 for i in range (N_PARTICLE ):
305330 plt .plot (particles [i ].x , particles [i ].y , ".r" )
@@ -315,6 +340,8 @@ def main():
315340 np .array (hxDR [1 , :]).flatten (), "-k" )
316341 plt .plot (np .array (hxEst [0 , :]).flatten (),
317342 np .array (hxEst [1 , :]).flatten (), "-r" )
343+
344+ plt .plot (xEst [0 ], xEst [1 ], "xk" )
318345 plt .axis ("equal" )
319346 plt .grid (True )
320347 plt .pause (0.001 )
0 commit comments