1212
1313
1414# EKF state covariance
15- Cx = np .diag ([0.5 , 0.5 , math .radians (30.0 )])** 2
16-
15+ Cx = np .diag ([1.0 , 1.0 , math .radians (30.0 )])** 2
1716
1817# Simulation parameter
1918Qsim = np .diag ([0.0 , math .radians (0.0 )])** 2
@@ -46,7 +45,8 @@ def __init__(self, N_LM):
4645
4746def normalize_weight (particles ):
4847
49- sumw = sum ([particles [ip ].w for ip in range (N_PARTICLE )])
48+ sumw = sum ([p .w for p in particles ])
49+ # print(sumw)
5050
5151 # if sumw <= 0.0000001:
5252 # for i in range(N_PARTICLE):
@@ -63,12 +63,16 @@ def calc_final_state(particles):
6363
6464 xEst = np .zeros ((STATE_SIZE , 1 ))
6565
66+ particles = normalize_weight (particles )
67+
6668 for i in range (N_PARTICLE ):
6769 xEst [0 , 0 ] += particles [i ].w * particles [i ].x
6870 xEst [1 , 0 ] += particles [i ].w * particles [i ].y
6971 xEst [2 , 0 ] += particles [i ].w * particles [i ].yaw
72+ # print(particles[i].x, particles[i].y, particles[i].yaw, particles[i].w)
7073
7174 xEst [2 , 0 ] = pi_2_pi (xEst [2 , 0 ])
75+ # print(xEst)
7276
7377 return xEst
7478
@@ -80,7 +84,7 @@ def predict_particles(particles, u):
8084 px [0 , 0 ] = particles [i ].x
8185 px [1 , 0 ] = particles [i ].y
8286 px [2 , 0 ] = particles [i ].yaw
83- ud = u + np .matrix (np .random .randn (1 , 2 )) * Rsim # add noise
87+ ud = u + ( np .matrix (np .random .randn (1 , 2 )) * Rsim ). T # add noise
8488 px = motion_model (px , ud )
8589 particles [i ].x = px [0 , 0 ]
8690 particles [i ].y = px [1 , 0 ]
@@ -112,38 +116,87 @@ def add_new_lm(particle, z):
112116 return particle
113117
114118
115- def feature_update (particle , z , R ):
119+ def compute_jacobians (particle , xf , Pf , R ):
120+ dx = xf [0 ] - particle .x
121+ dy = xf [1 ] - particle .y
122+ d2 = dx ** 2 + dy ** 2
123+ d = math .sqrt (d2 )
116124
117- return particle
125+ zp = np . matrix ([[ d , pi_2_pi ( math . atan2 ( dy , dx ) - particle . yaw )]])
118126
127+ Hv = np .matrix ([[- dx / d , - dy / d , 0.0 ],
128+ [dy / d2 , - dx / d2 , - 1.0 ]])
119129
120- def compute_weight (particle , z ):
130+ Hf = np .matrix ([[dx / d , - dy / d ],
131+ [- dy / d2 , dx / d2 ]])
121132
122- lm_id = int ( z [ 0 , 2 ])
133+ Sf = Hf * Pf * Hf . T + R
123134
124- lmxy = np .matrix (particle .lm [lm_id , :])
125- print (lmxy )
135+ return zp , Hv , Hf , Sf
136+
137+
138+ def KF_cholesky_update (xf , Pf , v , R , Hf ):
139+ PHt = Pf * Hf .T
140+ S = Hf * PHt + R
141+
142+ S = (S + S .T ) * 0.5
143+ SChol = np .linalg .cholesky (S ).T
144+
145+ SCholInv = np .linalg .inv (SChol )
146+ W1 = PHt * SCholInv
147+ W = W1 * SCholInv .T
148+
149+ x = xf + (W * v .T ).T
150+ P = Pf - W1 * W1 .T
151+
152+ return x , P
153+
154+
155+ def feature_update (particle , z , R ):
126156
127- # calc landmark xy
128- r = z [0 , 0 ]
129- b = z [0 , 1 ]
130157 lm_id = int (z [0 , 2 ])
158+ xf = particle .lm [lm_id , :]
159+ Pf = particle .lmP [lm_id ]
160+ # print(xf)
161+ # print(particle.lm)
131162
132- s = math .sin (particle .yaw + b )
133- c = math .cos (particle .yaw + b )
163+ zp , Hv , Hf , Sf = compute_jacobians (particle , xf , Pf , R )
164+
165+ v = z [0 , 0 :2 ] - zp
166+ v [0 , 1 ] = pi_2_pi (v [0 , 1 ])
167+ # print(v)
168+
169+ xf , Pf = KF_cholesky_update (xf , Pf , v , R , Hf )
170+
171+ particle .lm [lm_id , :] = xf
172+ particle .lmP [lm_id ] = Pf
173+
174+ # print(xf)
175+ # print(particle.lm)
176+ # print(Pf)
177+ # input()
134178
135- zxy = np .zeros ((1 , 2 ))
179+ return particle
180+
181+
182+ def compute_weight (particle , z , R ):
183+
184+ lm_id = int (z [0 , 2 ])
185+ xf = particle .lm [lm_id , :]
186+ Pf = particle .lmP [lm_id ]
187+ zp , Hv , Hf , Sf = compute_jacobians (particle , xf , Pf , R )
136188
137- zxy [0 , 0 ] = particle .x + r * c
138- zxy [0 , 1 ] = particle .y + r * s
189+ dx = z [0 , 0 :2 ] - zp
190+ dx [0 , 1 ] = pi_2_pi (dx [0 , 1 ])
191+ dx = dx .T
139192
140- dx = (lmxy - zxy ).T
141193 S = particle .lmP [lm_id ]
142194
143195 num = math .exp (- 0.5 * dx .T * np .linalg .inv (S ) * dx )
144196 den = 2.0 * math .pi * math .sqrt (np .linalg .det (S ))
145197
146198 w = num / den
199+ print (w )
147200
148201 return w
149202
@@ -160,8 +213,9 @@ def update_with_observation(particles, z):
160213 particles [ip ] = add_new_lm (particles [ip ], z [iz , :])
161214 # known landmark
162215 else :
163- w = compute_weight (particles [ip ], z [iz , :]) # w = p(z_k | x_k)
164- particles [ip ].w = particles [ip ].w + w
216+ # w = p(z_k | x_k)
217+ w = compute_weight (particles [ip ], z [iz , :], Cx [0 :2 , 0 :2 ])
218+ particles [ip ].w = particles [ip ].w * w
165219 particles [ip ] = feature_update (
166220 particles [ip ], z [iz , :], Cx [0 :2 , 0 :2 ])
167221
@@ -180,10 +234,9 @@ def resampling(particles):
180234 pw .append (particles [i ].w )
181235
182236 pw = np .matrix (pw )
183- # print(pw)
184237
185238 Neff = 1.0 / (pw * pw .T )[0 , 0 ] # Effective particle number
186- # print(Neff)
239+ print (Neff )
187240
188241 if Neff < NTH : # resampling
189242 print ("resamping" )
@@ -198,11 +251,16 @@ def resampling(particles):
198251 ind += 1
199252 inds .append (ind )
200253
254+ # print(inds)
255+ # print(pw)
256+
201257 tparticles = particles [:]
202258 for i in range (len (inds )):
203259 particles [i ] = tparticles [inds [i ]]
260+ particles [i ].w = 1.0 / N_PARTICLE
204261
205262 particles = normalize_weight (particles )
263+ # input()
206264
207265 return particles
208266
@@ -272,6 +330,8 @@ def motion_model(x, u):
272330
273331 x = F * x + B * u
274332
333+ x [2 , 0 ] = pi_2_pi (x [2 , 0 ])
334+
275335 return x
276336
277337
@@ -356,6 +416,10 @@ def main():
356416 for i in range (N_PARTICLE ):
357417 plt .plot (particles [i ].x , particles [i ].y , ".r" )
358418
419+ # for ii in range(N_LM):
420+ # plt.plot(particles[i].lm[ii, 0],
421+ # particles[i].lm[ii, 1], "xb")
422+
359423 # plot landmark
360424 for i in range (calc_n_LM (xEst )):
361425 plt .plot (xEst [STATE_SIZE + i * 2 ],
0 commit comments