Skip to content

Commit f0a654e

Browse files
committed
keep implementing
1 parent 3e9005d commit f0a654e

File tree

1 file changed

+168
-0
lines changed

1 file changed

+168
-0
lines changed

SLAM/EKFSLAM/ekf_slam.py

Lines changed: 168 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,10 +6,178 @@
66
77
"""
88

9+
import numpy as np
10+
import math
11+
import matplotlib.pyplot as plt
12+
13+
# Simulation parameter
14+
Qsim = np.diag([0.2])**2
15+
Rsim = np.diag([1.0, math.radians(30.0)])**2
16+
17+
DT = 0.1 # time tick [s]
18+
SIM_TIME = 50.0 # simulation time [s]
19+
MAX_RANGE = 20.0 # maximum observation range
20+
21+
# Particle filter parameter
22+
NP = 100 # Number of Particle
23+
NTh = NP / 2.0 # Number of particle for re-sampling
24+
25+
show_animation = True
26+
27+
28+
def calc_input():
29+
v = 1.0 # [m/s]
30+
yawrate = 0.1 # [rad/s]
31+
u = np.matrix([v, yawrate]).T
32+
return u
33+
34+
35+
def observation(xTrue, xd, u, RFID):
36+
37+
xTrue = motion_model(xTrue, u)
38+
39+
# add noise to gps x-y
40+
z = np.matrix(np.zeros((0, 3)))
41+
42+
for i in range(len(RFID[:, 0])):
43+
44+
dx = xTrue[0, 0] - RFID[i, 0]
45+
dy = xTrue[1, 0] - RFID[i, 1]
46+
d = math.sqrt(dx**2 + dy**2)
47+
if d <= MAX_RANGE:
48+
dn = d + np.random.randn() * Qsim[0, 0] # add noise
49+
zi = np.matrix([dn, RFID[i, 0], RFID[i, 1]])
50+
z = np.vstack((z, zi))
51+
52+
# add noise to input
53+
ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0]
54+
ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1]
55+
ud = np.matrix([ud1, ud2]).T
56+
57+
xd = motion_model(xd, ud)
58+
59+
return xTrue, z, xd, ud
60+
61+
62+
def motion_model(x, u):
63+
64+
F = np.matrix([[1.0, 0, 0, 0],
65+
[0, 1.0, 0, 0],
66+
[0, 0, 1.0, 0],
67+
[0, 0, 0, 0]])
68+
69+
B = np.matrix([[DT * math.cos(x[2, 0]), 0],
70+
[DT * math.sin(x[2, 0]), 0],
71+
[0.0, DT],
72+
[1.0, 0.0]])
73+
74+
x = F * x + B * u
75+
76+
return x
77+
78+
79+
def ekf_slam(xEst, PEst, u, z):
80+
# Predict
81+
xEst = motion_model(xEst, u)
82+
# [G,Fx]=jacobF(xEst, u);
83+
# PEst= G'*PEst*G + Fx'*R*Fx;
84+
85+
return xEst, PEst
86+
87+
# % Update
88+
# for iz=1:length(z(:,1))%それぞれの観測値に対して
89+
# %観測値をランドマークとして追加
90+
# zl=CalcLMPosiFromZ(xEst,z(iz,:));%観測値そのものからLMの位置を計算
91+
# %状態ベクトルと共分散行列の追加
92+
# xAug=[xEst;zl];
93+
# PAug=[PEst zeros(length(xEst),LMSize);
94+
# zeros(LMSize,length(xEst)) initP];
95+
96+
# mdist=[];%マハラノビス距離のリスト
97+
# for il=1:GetnLM(xAug) %それぞれのランドマークについて
98+
# if il==GetnLM(xAug)
99+
# mdist=[mdist alpha];%新しく追加した点の距離はパラメータ値を使う
100+
# else
101+
# lm=xAug(4+2*(il-1):5+2*(il-1));
102+
# [y,S,H]=CalcInnovation(lm,xAug,PAug,z(iz,1:2),il);
103+
# mdist=[mdist y'*inv(S)*y];%マハラノビス距離の計算
104+
# end
105+
# end
106+
107+
# %マハラノビス距離が最も近いものに対応付け
108+
# [C,I]=min(mdist);
109+
110+
# %一番距離が小さいものが追加したものならば、その観測値をランドマークとして採用
111+
# if I==GetnLM(xAug)
112+
# %disp('New LM')
113+
# xEst=xAug;
114+
# PEst=PAug;
115+
# end
116+
117+
# lm=xEst(4+2*(I-1):5+2*(I-1));%対応付けられたランドマークデータの取得
118+
# %イノベーションの計算
119+
# [y,S,H]=CalcInnovation(lm,xEst,PEst,z(iz,1:2),I);
120+
# K = PEst*H'*inv(S);
121+
# xEst = xEst + K*y;
122+
# PEst = (eye(size(xEst,1)) - K*H)*PEst;
123+
# end
124+
125+
# xEst(3)=PI2PI(xEst(3));%角度補正
126+
9127

10128
def main():
11129
print(__file__ + " start!!")
12130

131+
time = 0.0
132+
133+
# RFID positions [x, y]
134+
RFID = np.array([[10.0, 0.0],
135+
[10.0, 10.0],
136+
[0.0, 15.0],
137+
[-5.0, 20.0]])
138+
139+
# State Vector [x y yaw v]'
140+
xEst = np.matrix(np.zeros((4, 1)))
141+
xTrue = np.matrix(np.zeros((4, 1)))
142+
PEst = np.eye(4)
143+
144+
xDR = np.matrix(np.zeros((4, 1))) # Dead reckoning
145+
146+
# history
147+
hxEst = xEst
148+
hxTrue = xTrue
149+
hxDR = xTrue
150+
151+
while SIM_TIME >= time:
152+
time += DT
153+
u = calc_input()
154+
155+
xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID)
156+
157+
xEst, PEst = ekf_slam(xEst, PEst, ud, z)
158+
159+
# store data history
160+
hxEst = np.hstack((hxEst, xEst))
161+
hxDR = np.hstack((hxDR, xDR))
162+
hxTrue = np.hstack((hxTrue, xTrue))
163+
164+
if show_animation:
165+
plt.cla()
166+
167+
for i in range(len(z[:, 0])):
168+
plt.plot([xTrue[0, 0], z[i, 1]], [xTrue[1, 0], z[i, 2]], "-k")
169+
plt.plot(RFID[:, 0], RFID[:, 1], "*k")
170+
plt.plot(xEst[0], xEst[1], ".r")
171+
plt.plot(np.array(hxTrue[0, :]).flatten(),
172+
np.array(hxTrue[1, :]).flatten(), "-b")
173+
plt.plot(np.array(hxDR[0, :]).flatten(),
174+
np.array(hxDR[1, :]).flatten(), "-k")
175+
plt.plot(np.array(hxEst[0, :]).flatten(),
176+
np.array(hxEst[1, :]).flatten(), "-r")
177+
plt.axis("equal")
178+
plt.grid(True)
179+
plt.pause(0.001)
180+
13181

14182
if __name__ == '__main__':
15183
main()

0 commit comments

Comments
 (0)