11"""
2-
32Extended Kalman Filter SLAM example
4-
53author: Atsushi Sakai (@Atsushi_twi)
6-
74"""
85
96import numpy as np
@@ -50,13 +47,12 @@ def ekf_slam(xEst, PEst, u, z):
5047 np .hstack ((np .zeros ((LM_SIZE , len (xEst ))), initP ))))
5148 xEst = xAug
5249 PEst = PAug
53-
5450 lm = get_LM_Pos_from_state (xEst , minid )
5551 y , S , H = calc_innovation (lm , xEst , PEst , z [iz , 0 :2 ], minid )
5652
57- K = PEst * H .T * np .linalg .inv (S )
58- xEst = xEst + K * y
59- PEst = (np .eye (len (xEst )) - K * H ) * PEst
53+ K = PEst . dot ( H .T ). dot ( np .linalg .inv (S ) )
54+ xEst = xEst + K . dot ( y )
55+ PEst = (np .eye (len (xEst )) - K . dot ( H )). dot ( PEst )
6056
6157 xEst [2 ] = pi_2_pi (xEst [2 ])
6258
@@ -66,7 +62,7 @@ def ekf_slam(xEst, PEst, u, z):
6662def calc_input ():
6763 v = 1.0 # [m/s]
6864 yawrate = 0.1 # [rad/s]
69- u = np .matrix ([ v , yawrate ]).T
65+ u = np .array ([[ v , yawrate ] ]).T
7066 return u
7167
7268
@@ -75,7 +71,7 @@ def observation(xTrue, xd, u, RFID):
7571 xTrue = motion_model (xTrue , u )
7672
7773 # add noise to gps x-y
78- z = np .matrix ( np . zeros ((0 , 3 ) ))
74+ z = np .zeros ((0 , 3 ))
7975
8076 for i in range (len (RFID [:, 0 ])):
8177
@@ -86,31 +82,29 @@ def observation(xTrue, xd, u, RFID):
8682 if d <= MAX_RANGE :
8783 dn = d + np .random .randn () * Qsim [0 , 0 ] # add noise
8884 anglen = angle + np .random .randn () * Qsim [1 , 1 ] # add noise
89- zi = np .matrix ([dn , anglen , i ])
85+ zi = np .array ([dn , anglen , i ])
9086 z = np .vstack ((z , zi ))
9187
9288 # add noise to input
93- ud1 = u [ 0 , 0 ] + np .random . randn () * Rsim [ 0 , 0 ]
94- ud2 = u [ 1 , 0 ] + np .random .randn () * Rsim [1 , 1 ]
95- ud = np .matrix ([ ud1 , ud2 ]).T
89+ ud = np .array ([[
90+ u [ 0 , 0 ] + np .random .randn () * Rsim [0 , 0 ],
91+ u [ 1 , 0 ] + np .random . randn () * Rsim [ 1 , 1 ]] ]).T
9692
9793 xd = motion_model (xd , ud )
98-
9994 return xTrue , z , xd , ud
10095
10196
10297def motion_model (x , u ):
10398
104- F = np .matrix ([[1.0 , 0 , 0 ],
99+ F = np .array ([[1.0 , 0 , 0 ],
105100 [0 , 1.0 , 0 ],
106101 [0 , 0 , 1.0 ]])
107102
108- B = np .matrix ([[DT * math .cos (x [2 , 0 ]), 0 ],
103+ B = np .array ([[DT * math .cos (x [2 , 0 ]), 0 ],
109104 [DT * math .sin (x [2 , 0 ]), 0 ],
110105 [0.0 , DT ]])
111106
112- x = F * x + B * u
113-
107+ x = F .dot (x ) + B .dot (u )
114108 return x
115109
116110
@@ -124,7 +118,7 @@ def jacob_motion(x, u):
124118 Fx = np .hstack ((np .eye (STATE_SIZE ), np .zeros (
125119 (STATE_SIZE , LM_SIZE * calc_n_LM (x )))))
126120
127- jF = np .matrix ([[0.0 , 0.0 , - DT * u [0 ] * math .sin (x [2 , 0 ])],
121+ jF = np .array ([[0.0 , 0.0 , - DT * u [0 ] * math .sin (x [2 , 0 ])],
128122 [0.0 , 0.0 , DT * u [0 ] * math .cos (x [2 , 0 ])],
129123 [0.0 , 0.0 , 0.0 ]])
130124
@@ -134,11 +128,12 @@ def jacob_motion(x, u):
134128
135129
136130def calc_LM_Pos (x , z ):
137-
138131 zp = np .zeros ((2 , 1 ))
139132
140- zp [0 , 0 ] = x [0 , 0 ] + z [0 , 0 ] * math .cos (x [2 , 0 ] + z [0 , 1 ])
141- zp [1 , 0 ] = x [1 , 0 ] + z [0 , 0 ] * math .sin (x [2 , 0 ] + z [0 , 1 ])
133+ zp [0 , 0 ] = x [0 , 0 ] + z [0 ] * math .cos (x [2 , 0 ] + z [1 ])
134+ zp [1 , 0 ] = x [1 , 0 ] + z [0 ] * math .sin (x [2 , 0 ] + z [1 ])
135+ #zp[0, 0] = x[0, 0] + z[0, 0] * math.cos(x[2, 0] + z[0, 1])
136+ #zp[1, 0] = x[1, 0] + z[0, 0] * math.sin(x[2, 0] + z[0, 1])
142137
143138 return zp
144139
@@ -162,7 +157,7 @@ def search_correspond_LM_ID(xAug, PAug, zi):
162157 for i in range (nLM ):
163158 lm = get_LM_Pos_from_state (xAug , i )
164159 y , S , H = calc_innovation (lm , xAug , PAug , zi , i )
165- mdist .append (y .T * np .linalg .inv (S ) * y )
160+ mdist .append (y .T . dot ( np .linalg .inv (S )). dot ( y ) )
166161
167162 mdist .append (M_DIST_TH ) # new landmark
168163
@@ -173,20 +168,21 @@ def search_correspond_LM_ID(xAug, PAug, zi):
173168
174169def calc_innovation (lm , xEst , PEst , z , LMid ):
175170 delta = lm - xEst [0 :2 ]
176- q = (delta .T * delta )[0 , 0 ]
177- zangle = math .atan2 (delta [1 ], delta [0 ]) - xEst [2 ]
178- zp = [math .sqrt (q ), pi_2_pi (zangle )]
171+ q = (delta .T .dot (delta ))[0 , 0 ]
172+ #zangle = math.atan2(delta[1], delta[0]) - xEst[2]
173+ zangle = math .atan2 (delta [1 ,0 ], delta [0 ,0 ]) - xEst [2 ]
174+ zp = np .array ([[math .sqrt (q ), pi_2_pi (zangle )]])
179175 y = (z - zp ).T
180176 y [1 ] = pi_2_pi (y [1 ])
181177 H = jacobH (q , delta , xEst , LMid + 1 )
182- S = H * PEst * H .T + Cx [0 :2 , 0 :2 ]
178+ S = H . dot ( PEst ). dot ( H .T ) + Cx [0 :2 , 0 :2 ]
183179
184180 return y , S , H
185181
186182
187183def jacobH (q , delta , x , i ):
188184 sq = math .sqrt (q )
189- G = np .matrix ([[- sq * delta [0 , 0 ], - sq * delta [1 , 0 ], 0 , sq * delta [0 , 0 ], sq * delta [1 , 0 ]],
185+ G = np .array ([[- sq * delta [0 , 0 ], - sq * delta [1 , 0 ], 0 , sq * delta [0 , 0 ], sq * delta [1 , 0 ]],
190186 [delta [1 , 0 ], - delta [0 , 0 ], - 1.0 , - delta [1 , 0 ], delta [0 , 0 ]]])
191187
192188 G = G / q
@@ -197,7 +193,7 @@ def jacobH(q, delta, x, i):
197193
198194 F = np .vstack ((F1 , F2 ))
199195
200- H = G * F
196+ H = G . dot ( F )
201197
202198 return H
203199
@@ -218,11 +214,11 @@ def main():
218214 [- 5.0 , 20.0 ]])
219215
220216 # State Vector [x y yaw v]'
221- xEst = np .matrix ( np . zeros ((STATE_SIZE , 1 ) ))
222- xTrue = np .matrix ( np . zeros ((STATE_SIZE , 1 ) ))
217+ xEst = np .zeros ((STATE_SIZE , 1 ))
218+ xTrue = np .zeros ((STATE_SIZE , 1 ))
223219 PEst = np .eye (STATE_SIZE )
224220
225- xDR = np .matrix ( np . zeros ((STATE_SIZE , 1 ) )) # Dead reckoning
221+ xDR = np .zeros ((STATE_SIZE , 1 )) # Dead reckoning
226222
227223 # history
228224 hxEst = xEst
@@ -239,6 +235,7 @@ def main():
239235
240236 x_state = xEst [0 :STATE_SIZE ]
241237
238+
242239 # store data history
243240 hxEst = np .hstack ((hxEst , x_state ))
244241 hxDR = np .hstack ((hxDR , xDR ))
@@ -255,16 +252,17 @@ def main():
255252 plt .plot (xEst [STATE_SIZE + i * 2 ],
256253 xEst [STATE_SIZE + i * 2 + 1 ], "xg" )
257254
258- plt .plot (np . array ( hxTrue [0 , :]). flatten () ,
259- np . array ( hxTrue [1 , :]). flatten () , "-b" )
260- plt .plot (np . array ( hxDR [0 , :]). flatten () ,
261- np . array ( hxDR [1 , :]). flatten () , "-k" )
262- plt .plot (np . array ( hxEst [0 , :]). flatten () ,
263- np . array ( hxEst [1 , :]). flatten () , "-r" )
255+ plt .plot (hxTrue [0 , :],
256+ hxTrue [1 , :], "-b" )
257+ plt .plot (hxDR [0 , :],
258+ hxDR [1 , :], "-k" )
259+ plt .plot (hxEst [0 , :],
260+ hxEst [1 , :], "-r" )
264261 plt .axis ("equal" )
265262 plt .grid (True )
266263 plt .pause (0.001 )
267264
268265
266+
269267if __name__ == '__main__' :
270- main ()
268+ main ()
0 commit comments