2424STATE_SIZE = 3 # State size [x,y,yaw]
2525LM_SIZE = 2 # LM srate size [x,y]
2626
27+ C_SIGMA1 = 1.0
28+ C_SIGMA2 = 0.1
29+ C_SIGMA3 = 0.1
30+
2731MAX_ITR = 20
2832
2933show_animation = True
@@ -33,29 +37,37 @@ class Edge():
3337
3438 def __init__ (self ):
3539 self .e = np .zeros ((3 , 1 ))
40+ self .omega = np .zeros ((3 , 3 )) # information matrix
41+ self .d_t = 0.0
42+ self .d_td = 0.0
43+ self .yaw_t = 0.0
44+ self .yaw_td = 0.0
45+ self .angle_t = 0.0
46+ self .angle_td = 0.0
47+
48+
49+ def cal_ob_sigma (d ):
50+
51+ sigma = np .zeros ((3 , 3 ))
52+ sigma [0 , 0 ] = (d * C_SIGMA1 )** 2
53+ sigma [1 , 1 ] = (d * C_SIGMA2 )** 2
54+ sigma [2 , 2 ] = C_SIGMA3 ** 2
55+
56+ return sigma
3657
3758
3859def calc_edges (xlist , zlist ):
3960
4061 edges = []
4162 zids = list (itertools .combinations (range (len (zlist )), 2 ))
42- # print(zids)
4363
4464 for (t , td ) in zids :
45- xt = xlist [0 , t ]
46- yt = xlist [1 , t ]
47- yawt = xlist [2 , t ]
48- xtd = xlist [0 , td ]
49- ytd = xlist [1 , td ]
50- yawtd = xlist [2 , td ]
65+ xt , yt , yawt = xlist [0 , t ], xlist [1 , t ], xlist [2 , t ]
66+ xtd , ytd , yawtd = xlist [0 , td ], xlist [1 , td ], xlist [2 , td ]
5167
52- dt = zlist [t ][0 , 0 ]
53- anglet = zlist [t ][1 , 0 ]
54- phit = zlist [t ][2 , 0 ]
68+ dt , anglet , phit = zlist [t ][0 , 0 ], zlist [t ][1 , 0 ], zlist [t ][2 , 0 ]
5569
56- dtd = zlist [td ][0 , 0 ]
57- angletd = zlist [td ][0 , 0 ]
58- phitd = zlist [td ][2 , 0 ]
70+ dtd , angletd , phitd = zlist [td ][0 , 0 ], zlist [td ][1 , 0 ], zlist [td ][2 , 0 ]
5971
6072 edge = Edge ()
6173
@@ -68,25 +80,58 @@ def calc_edges(xlist, zlist):
6880 edge .e [1 , 0 ] = ytd - yt - t3 + t4
6981 edge .e [2 , 0 ] = yawtd - yawt - phit + phitd
7082
83+ sig_t = cal_ob_sigma (dt )
84+ sig_td = cal_ob_sigma (dtd )
85+
86+ Rt = np .matrix ([[math .cos (yawt + anglet ), math .sin (yawt + anglet ), 0 ],
87+ [- math .sin (yawt + anglet ), math .cos (yawt + anglet ), 0 ],
88+ [0 , 0 , 1.0 ]])
89+ Rtd = np .matrix ([[math .cos (yawtd + angletd ), math .sin (yawtd + angletd ), 0 ],
90+ [- math .sin (yawtd + angletd ),
91+ math .cos (yawtd + angletd ), 0 ],
92+ [0 , 0 , 1.0 ]])
93+
94+ edge .omega = np .linalg .inv (Rt * sig_t * Rt .T + Rtd * sig_td * Rtd .T )
95+ edge .d_t , edge .d_td = dt , dtd
96+ edge .yaw_t , edge .yaw_td = yawt , yawtd
97+ edge .angle_t , edge .angle_td = anglet , angletd
98+
7199 edges .append (edge )
72100
73101 return edges
74102
75103
104+ def calc_jacobian (edge ):
105+ t = edge .yaw_t + edge .angle_t
106+ A = np .matrix ([[- 1.0 , 0 , edge .d_t * math .sin (t )],
107+ [0 , - 1.0 , - edge .d_t * math .cos (t )],
108+ [0 , 0 , - 1.0 ]])
109+
110+ td = edge .yaw_td + edge .angle_td
111+ B = np .matrix ([[1.0 , 0 , - edge .d_td * math .sin (td )],
112+ [0 , 1.0 , edge .d_td * math .cos (td )],
113+ [0 , 0 , 1.0 ]])
114+
115+ # print(A)
116+ # print(B)
117+
118+ return A , B
119+
120+
76121def graph_based_slam (xEst , PEst , u , z , hxDR , hz ):
77122
78123 x_opt = copy .deepcopy (hxDR )
124+ edges = calc_edges (x_opt , hz )
125+ n = len (hz ) * 3
79126
80- for itr in range (20 ):
81- edges = calc_edges (x_opt , hz )
127+ for itr in range (MAX_ITR ):
82128 print ("nedges:" , len (edges ))
83129
84- n = len (hz ) * 3
85130 H = np .zeros ((n , n ))
86131 b = np .zeros ((n , 1 ))
87132
88- # for e in pos_edges :
89- # e.addInfo(matH,vecb )
133+ for edge in edges :
134+ A , B = calc_jacobian ( edge )
90135
91136 # H[0:3, 0:3] += np.identity(3) * 10000 # to fix origin
92137 H += np .identity (n ) * 10000 # to fix origin
0 commit comments