Skip to content

Commit 0df3f27

Browse files
committed
keep coding
1 parent ae44021 commit 0df3f27

File tree

1 file changed

+85
-44
lines changed

1 file changed

+85
-44
lines changed

SLAM/EKFSLAM/ekf_slam.py

Lines changed: 85 additions & 44 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,8 @@
2020
SIM_TIME = 50.0 # simulation time [s]
2121
MAX_RANGE = 20.0 # maximum observation range
2222

23+
M_DIST_TH = 1.0
24+
2325
POSE_SIZE = 3 # [x,y,yaw]
2426
LM_SIZE = 2 # [x,y]
2527

@@ -98,54 +100,91 @@ def jacob_motion(x, u):
98100
return G, Fx,
99101

100102

101-
def ekf_slam(xEst, PEst, u, z):
102-
# Predict
103-
xEst = motion_model(xEst, u)
104-
G, Fx = jacob_motion(xEst, u)
105-
PEst = G.T * PEst * G + Fx.T * Cx * Fx
103+
def calc_LM_Pos(x, z):
106104

107-
return xEst, PEst
105+
zp = np.zeros((2, 1))
106+
107+
zp[0, 0] = x[0, 0] + z[0, 0] * math.cos(x[2, 0] + z[0, 1])
108+
zp[1, 0] = x[1, 0] + z[0, 0] * math.sin(x[2, 0] + z[0, 1])
109+
110+
return zp
111+
112+
113+
def calc_mahalanobis_dist(xAug, PAug):
114+
115+
nLM = calc_n_LM(xAug)
116+
117+
mdist = []
108118

109-
# % Update
110-
# for iz=1:length(z(:,1))%それぞれの観測値に対して
111-
# %観測値をランドマークとして追加
112-
# zl=CalcLMPosiFromZ(xEst,z(iz,:));%観測値そのものからLMの位置を計算
113-
# %状態ベクトルと共分散行列の追加
114-
# xAug=[xEst;zl];
115-
# PAug=[PEst zeros(length(xEst),LMSize);
116-
# zeros(LMSize,length(xEst)) initP];
117-
118-
# mdist=[];%マハラノビス距離のリスト
119-
# for il=1:GetnLM(xAug) %それぞれのランドマークについて
120-
# if il==GetnLM(xAug)
121-
# mdist=[mdist alpha];%新しく追加した点の距離はパラメータ値を使う
122-
# else
123-
# lm=xAug(4+2*(il-1):5+2*(il-1));
124-
# [y,S,H]=CalcInnovation(lm,xAug,PAug,z(iz,1:2),il);
125-
# mdist=[mdist y'*inv(S)*y];%マハラノビス距離の計算
126-
# end
127-
# end
128-
129-
# %マハラノビス距離が最も近いものに対応付け
130-
# [C,I]=min(mdist);
131-
132-
# %一番距離が小さいものが追加したものならば、その観測値をランドマークとして採用
133-
# if I==GetnLM(xAug)
134-
# %disp('New LM')
135-
# xEst=xAug;
136-
# PEst=PAug;
137-
# end
138-
139-
# lm=xEst(4+2*(I-1):5+2*(I-1));%対応付けられたランドマークデータの取得
140-
# %イノベーションの計算
141-
# [y,S,H]=CalcInnovation(lm,xEst,PEst,z(iz,1:2),I);
142-
# K = PEst*H'*inv(S);
143-
# xEst = xEst + K*y;
144-
# PEst = (eye(size(xEst,1)) - K*H)*PEst;
145-
# end
119+
for i in range(nLM):
120+
121+
if i == nLM - 1:
122+
mdist.append(M_DIST_TH)
123+
else:
124+
lm = xAug[POSE_SIZE + LM_SIZE *
125+
i: POSE_SIZE + LM_SIZE * (i + 1), :]
126+
# y, S, H = calc_innovation(lm, xAug, PAug, z[iz, 0:2], il)
127+
# mdist=[mdist y'*inv(S)*y];%マハラノビス距離の計算
128+
129+
return mdist
130+
131+
# function [y,S,H]=CalcInnovation(lm,xEst,PEst,z,LMId)
132+
# %対応付け結果からイノベーションを計算する関数
133+
# global Q;
134+
# delta=lm-xEst(1:2);
135+
# q=delta'*delta;
136+
# zangle=atan2(delta(2),delta(1))-xEst(3);
137+
# zp=[sqrt(q) PI2PI(zangle)];%観測値の予測
138+
# y=(z-zp)';
139+
# H=jacobH(q,delta,xEst,LMId);
140+
# S=H*PEst*H'+Q;
141+
142+
143+
def ekf_slam(xEst, PEst, u, z):
144+
# Predict
145+
xEst[0:POSE_SIZE] = motion_model(xEst[0:POSE_SIZE], u)
146+
G, Fx = jacob_motion(xEst[0:POSE_SIZE], u)
147+
PEst[0:POSE_SIZE, 0:POSE_SIZE] = G.T * \
148+
PEst[0:POSE_SIZE, 0:POSE_SIZE] * G + Fx.T * Cx * Fx
149+
initP = np.eye(2) * 1000.0
150+
151+
# Update
152+
for iz in range(len(z[:, 0])): # for each observation
153+
# print(iz)
154+
155+
zp = calc_LM_Pos(xEst, z[iz, :])
156+
157+
# Extend state and covariance matrix
158+
xAug = np.vstack((xEst, zp))
159+
PAug = np.vstack((np.hstack((PEst, np.zeros((len(xEst), LM_SIZE)))),
160+
np.hstack((np.zeros((LM_SIZE, len(xEst))), initP))))
161+
162+
mah_dists = calc_mahalanobis_dist(xAug, PAug)
163+
minid = mah_dists.index(min(mah_dists))
164+
# print(minid)
165+
166+
nLM = calc_n_LM(xAug)
167+
if minid == (nLM - 1):
168+
print("New LM")
169+
xEst = xAug
170+
PEst = PAug
171+
else:
172+
print("Old LM")
173+
174+
# print("DB LM")
175+
# lm=xEst(4+2*(I-1):5+2*(I-1));%対応付けられたランドマークデータの取得
176+
# %イノベーションの計算
177+
# [y,S,H]=CalcInnovation(lm,xEst,PEst,z(iz,1:2),I);
178+
# K = PEst*H'*inv(S);
179+
# xEst = xEst + K*y;
180+
# PEst = (eye(size(xEst,1)) - K*H)*PEst;
181+
# end
146182

147183
# xEst(3)=PI2PI(xEst(3));%角度補正
148184

185+
print(len(xEst))
186+
return xEst, PEst
187+
149188

150189
def main():
151190
print(__file__ + " start!!")
@@ -178,8 +217,10 @@ def main():
178217

179218
xEst, PEst = ekf_slam(xEst, PEst, ud, z)
180219

220+
x_state = xEst[0:POSE_SIZE]
221+
181222
# store data history
182-
hxEst = np.hstack((hxEst, xEst))
223+
hxEst = np.hstack((hxEst, x_state))
183224
hxDR = np.hstack((hxDR, xDR))
184225
hxTrue = np.hstack((hxTrue, xTrue))
185226

0 commit comments

Comments
 (0)