88
99import numpy as np
1010import math
11+ import copy
1112import matplotlib .pyplot as plt
1213
1314
2526STATE_SIZE = 3 # State size [x,y,yaw]
2627LM_SIZE = 2 # LM srate size [x,y]
2728
29+ MAX_ITR = 20
30+
2831show_animation = True
2932
3033
31- def graph_based_slam (xEst , PEst , u , z ):
34+ def graph_based_slam (xEst , PEst , u , z , hxDR , hz ):
35+
36+ x_opt = copy .deepcopy (hxDR )
37+
38+ for itr in range (20 ):
39+ # pos_edges = []
40+
41+ # # このfor文では、HalfEdgeからグラフの辺を作っていきます。
42+ # for i in range(len(actual_landmarks.positions)): # ランドマークごとにHalfEdgeからEdgeを作る
43+ # es = list(filter(lambda e: e.landmark_id == i, obs_edges)) # 同じランドマークIDを持つHalfEdgeの抽出
44+ # ps = list(itertools.combinations(es,2)) # esの要素のペアを全通り作る
45+ # for p in ps:
46+ # pos_edges.append(Edge(p[0],p[1])) # エッジを登録
47+
48+ n = len (hz ) * 3
49+ H = np .zeros ((n , n ))
50+ b = np .zeros ((n , 1 ))
51+
52+ # for e in pos_edges:
53+ # e.addInfo(matH,vecb)
3254
33- # Predict
34- S = STATE_SIZE
35- xEst [0 :S ] = motion_model (xEst [0 :S ], u )
55+ # H[0:3, 0:3] += np.identity(3) * 10000 # to fix origin
56+ H += np .identity (n ) * 10000 # to fix origin
3657
37- # Update
38- for iz in range (len (z [:, 0 ])): # for each observation
39- pass
58+ dx = - np .linalg .inv (H ).dot (b )
59+ # print(dx)
4060
41- xEst [2 ] = pi_2_pi (xEst [2 ])
61+ for i in range (len (hz )):
62+ x_opt [0 , i ] += dx [i * 3 , 0 ]
63+ x_opt [1 , i ] += dx [i * 3 + 1 , 0 ]
64+ x_opt [2 , i ] += dx [i * 3 + 2 , 0 ]
4265
43- return xEst , None
66+ # # HalfEdgeに登録してある推定値も更新
67+ # for e in obs_edges:
68+ # e.update(robot.guess_poses)
69+
70+ diff = dx .T .dot (dx )
71+ print ("iteration: %d, diff: %f" % (itr + 1 , diff ))
72+ if dx [0 , 0 ] < 1.0e-5 :
73+ break
74+
75+ return x_opt , None
4476
4577
4678def calc_input ():
@@ -94,94 +126,6 @@ def motion_model(x, u):
94126 return x
95127
96128
97- def calc_n_LM (x ):
98- n = int ((len (x ) - STATE_SIZE ) / LM_SIZE )
99- return n
100-
101-
102- def jacob_motion (x , u ):
103-
104- Fx = np .hstack ((np .eye (STATE_SIZE ), np .zeros (
105- (STATE_SIZE , LM_SIZE * calc_n_LM (x )))))
106-
107- jF = np .matrix ([[0.0 , 0.0 , - DT * u [0 ] * math .sin (x [2 , 0 ])],
108- [0.0 , 0.0 , DT * u [0 ] * math .cos (x [2 , 0 ])],
109- [0.0 , 0.0 , 0.0 ]])
110-
111- G = np .eye (STATE_SIZE ) + Fx .T * jF * Fx
112-
113- return G , Fx ,
114-
115-
116- def calc_LM_Pos (x , z ):
117-
118- zp = np .zeros ((2 , 1 ))
119-
120- zp [0 , 0 ] = x [0 , 0 ] + z [0 , 0 ] * math .cos (x [2 , 0 ] + z [0 , 1 ])
121- zp [1 , 0 ] = x [1 , 0 ] + z [0 , 0 ] * math .sin (x [2 , 0 ] + z [0 , 1 ])
122-
123- return zp
124-
125-
126- def get_LM_Pos_from_state (x , ind ):
127-
128- lm = x [STATE_SIZE + LM_SIZE * ind : STATE_SIZE + LM_SIZE * (ind + 1 ), :]
129-
130- return lm
131-
132-
133- def search_correspond_LM_ID (xAug , PAug , zi ):
134- """
135- Landmark association with Mahalanobis distance
136- """
137-
138- nLM = calc_n_LM (xAug )
139-
140- mdist = []
141-
142- for i in range (nLM ):
143- lm = get_LM_Pos_from_state (xAug , i )
144- y , S , H = calc_innovation (lm , xAug , PAug , zi , i )
145- mdist .append (y .T * np .linalg .inv (S ) * y )
146-
147- mdist .append (M_DIST_TH ) # new landmark
148-
149- minid = mdist .index (min (mdist ))
150-
151- return minid
152-
153-
154- def calc_innovation (lm , xEst , PEst , z , LMid ):
155- delta = lm - xEst [0 :2 ]
156- q = (delta .T * delta )[0 , 0 ]
157- zangle = math .atan2 (delta [1 ], delta [0 ]) - xEst [2 ]
158- zp = [math .sqrt (q ), pi_2_pi (zangle )]
159- y = (z - zp ).T
160- y [1 ] = pi_2_pi (y [1 ])
161- H = jacobH (q , delta , xEst , LMid + 1 )
162- S = H * PEst * H .T + Cx [0 :2 , 0 :2 ]
163-
164- return y , S , H
165-
166-
167- def jacobH (q , delta , x , i ):
168- sq = math .sqrt (q )
169- G = np .matrix ([[- sq * delta [0 , 0 ], - sq * delta [1 , 0 ], 0 , sq * delta [0 , 0 ], sq * delta [1 , 0 ]],
170- [delta [1 , 0 ], - delta [0 , 0 ], - 1.0 , - delta [1 , 0 ], delta [0 , 0 ]]])
171-
172- G = G / q
173- nLM = calc_n_LM (x )
174- F1 = np .hstack ((np .eye (3 ), np .zeros ((3 , 2 * nLM ))))
175- F2 = np .hstack ((np .zeros ((2 , 3 )), np .zeros ((2 , 2 * (i - 1 ))),
176- np .eye (2 ), np .zeros ((2 , 2 * nLM - 2 * i ))))
177-
178- F = np .vstack ((F1 , F2 ))
179-
180- H = G * F
181-
182- return H
183-
184-
185129def pi_2_pi (angle ):
186130 while (angle > math .pi ):
187131 angle = angle - 2.0 * math .pi
@@ -211,23 +155,22 @@ def main():
211155 xDR = np .matrix (np .zeros ((STATE_SIZE , 1 ))) # Dead reckoning
212156
213157 # history
214- hxEst = xEst
215158 hxTrue = xTrue
216159 hxDR = xTrue
160+ hz = []
217161
218162 while SIM_TIME >= time :
219163 time += DT
220164 u = calc_input ()
221165
222166 xTrue , z , xDR , ud = observation (xTrue , xDR , u , RFID )
223167
224- xEst , PEst = graph_based_slam (xEst , PEst , ud , z )
168+ hxDR = np .hstack ((hxDR , xDR ))
169+ hz .append (z )
225170
226- x_state = xEst [ 0 : STATE_SIZE ]
171+ x_opt , PEst = graph_based_slam ( xEst , PEst , ud , z , hxDR , hz )
227172
228173 # store data history
229- hxEst = np .hstack ((hxEst , x_state ))
230- hxDR = np .hstack ((hxDR , xDR ))
231174 hxTrue = np .hstack ((hxTrue , xTrue ))
232175
233176 if show_animation :
@@ -240,8 +183,8 @@ def main():
240183 np .array (hxTrue [1 , :]).flatten (), "-b" )
241184 plt .plot (np .array (hxDR [0 , :]).flatten (),
242185 np .array (hxDR [1 , :]).flatten (), "-k" )
243- plt .plot (np .array (hxEst [0 , :]).flatten (),
244- np .array (hxEst [1 , :]).flatten (), "-r" )
186+ plt .plot (np .array (x_opt [0 , :]).flatten (),
187+ np .array (x_opt [1 , :]).flatten (), "-r" )
245188 plt .axis ("equal" )
246189 plt .grid (True )
247190 plt .pause (0.001 )
0 commit comments