Skip to content

Commit 0bd52c3

Browse files
committed
start implementing fast slam
1 parent 978bab0 commit 0bd52c3

File tree

1 file changed

+204
-0
lines changed

1 file changed

+204
-0
lines changed

SLAM/FastSLAM/fast_slam.py

Lines changed: 204 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,204 @@
1+
"""
2+
3+
Fast SLAM example
4+
5+
author: Atsushi Sakai (@Atsushi_twi)
6+
7+
"""
8+
9+
import numpy as np
10+
import math
11+
import matplotlib.pyplot as plt
12+
13+
14+
# EKF state covariance
15+
Cx = np.diag([0.5, 0.5, math.radians(30.0)])**2
16+
17+
# Simulation parameter
18+
Qsim = np.diag([0.2, math.radians(1.0)])**2
19+
Rsim = np.diag([1.0, math.radians(10.0)])**2
20+
21+
DT = 0.1 # time tick [s]
22+
SIM_TIME = 50.0 # simulation time [s]
23+
MAX_RANGE = 20.0 # maximum observation range
24+
M_DIST_TH = 2.0 # Threshold of Mahalanobis distance for data association.
25+
STATE_SIZE = 3 # State size [x,y,yaw]
26+
LM_SIZE = 2 # LM srate size [x,y]
27+
28+
show_animation = True
29+
30+
31+
def fast_slam(xEst, PEst, u, z):
32+
33+
xEst[2] = pi_2_pi(xEst[2])
34+
35+
return xEst, PEst
36+
37+
38+
def calc_input():
39+
v = 1.0 # [m/s]
40+
yawrate = 0.1 # [rad/s]
41+
u = np.matrix([v, yawrate]).T
42+
return u
43+
44+
45+
def observation(xTrue, xd, u, RFID):
46+
47+
xTrue = motion_model(xTrue, u)
48+
49+
# add noise to gps x-y
50+
z = np.matrix(np.zeros((0, 3)))
51+
52+
for i in range(len(RFID[:, 0])):
53+
54+
dx = RFID[i, 0] - xTrue[0, 0]
55+
dy = RFID[i, 1] - xTrue[1, 0]
56+
d = math.sqrt(dx**2 + dy**2)
57+
angle = pi_2_pi(math.atan2(dy, dx))
58+
if d <= MAX_RANGE:
59+
dn = d + np.random.randn() * Qsim[0, 0] # add noise
60+
anglen = angle + np.random.randn() * Qsim[1, 1] # add noise
61+
zi = np.matrix([dn, anglen, i])
62+
z = np.vstack((z, zi))
63+
64+
# add noise to input
65+
ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0]
66+
ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1]
67+
ud = np.matrix([ud1, ud2]).T
68+
69+
xd = motion_model(xd, ud)
70+
71+
return xTrue, z, xd, ud
72+
73+
74+
def motion_model(x, u):
75+
76+
F = np.matrix([[1.0, 0, 0],
77+
[0, 1.0, 0],
78+
[0, 0, 1.0]])
79+
80+
B = np.matrix([[DT * math.cos(x[2, 0]), 0],
81+
[DT * math.sin(x[2, 0]), 0],
82+
[0.0, DT]])
83+
84+
x = F * x + B * u
85+
86+
return x
87+
88+
89+
def calc_n_LM(x):
90+
n = int((len(x) - STATE_SIZE) / LM_SIZE)
91+
return n
92+
93+
94+
def calc_LM_Pos(x, z):
95+
96+
zp = np.zeros((2, 1))
97+
98+
zp[0, 0] = x[0, 0] + z[0, 0] * math.cos(x[2, 0] + z[0, 1])
99+
zp[1, 0] = x[1, 0] + z[0, 0] * math.sin(x[2, 0] + z[0, 1])
100+
101+
return zp
102+
103+
104+
def get_LM_Pos_from_state(x, ind):
105+
106+
lm = x[STATE_SIZE + LM_SIZE * ind: STATE_SIZE + LM_SIZE * (ind + 1), :]
107+
108+
return lm
109+
110+
111+
def search_correspond_LM_ID(xAug, PAug, zi):
112+
"""
113+
Landmark association with Mahalanobis distance
114+
"""
115+
116+
nLM = calc_n_LM(xAug)
117+
118+
mdist = []
119+
120+
for i in range(nLM):
121+
# lm = get_LM_Pos_from_state(xAug, i)
122+
# # y, S, H = calc_innovation(lm, xAug, PAug, zi, i)
123+
# mdist.append(y.T * np.linalg.inv(S) * y)
124+
pass
125+
126+
mdist.append(M_DIST_TH) # new landmark
127+
128+
minid = mdist.index(min(mdist))
129+
130+
return minid
131+
132+
133+
def pi_2_pi(angle):
134+
while(angle > math.pi):
135+
angle = angle - 2.0 * math.pi
136+
137+
while(angle < -math.pi):
138+
angle = angle + 2.0 * math.pi
139+
140+
return angle
141+
142+
143+
def main():
144+
print(__file__ + " start!!")
145+
146+
time = 0.0
147+
148+
# RFID positions [x, y]
149+
RFID = np.array([[10.0, -2.0],
150+
[15.0, 10.0],
151+
[3.0, 15.0],
152+
[-5.0, 20.0]])
153+
154+
# State Vector [x y yaw v]'
155+
xEst = np.matrix(np.zeros((STATE_SIZE, 1)))
156+
xTrue = np.matrix(np.zeros((STATE_SIZE, 1)))
157+
PEst = np.eye(STATE_SIZE)
158+
159+
xDR = np.matrix(np.zeros((STATE_SIZE, 1))) # Dead reckoning
160+
161+
# history
162+
hxEst = xEst
163+
hxTrue = xTrue
164+
hxDR = xTrue
165+
166+
while SIM_TIME >= time:
167+
time += DT
168+
u = calc_input()
169+
170+
xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID)
171+
172+
xEst, PEst = fast_slam(xEst, PEst, ud, z)
173+
174+
x_state = xEst[0:STATE_SIZE]
175+
176+
# store data history
177+
hxEst = np.hstack((hxEst, x_state))
178+
hxDR = np.hstack((hxDR, xDR))
179+
hxTrue = np.hstack((hxTrue, xTrue))
180+
181+
if show_animation:
182+
plt.cla()
183+
184+
plt.plot(RFID[:, 0], RFID[:, 1], "*k")
185+
plt.plot(xEst[0], xEst[1], ".r")
186+
187+
# plot landmark
188+
for i in range(calc_n_LM(xEst)):
189+
plt.plot(xEst[STATE_SIZE + i * 2],
190+
xEst[STATE_SIZE + i * 2 + 1], "xg")
191+
192+
plt.plot(np.array(hxTrue[0, :]).flatten(),
193+
np.array(hxTrue[1, :]).flatten(), "-b")
194+
plt.plot(np.array(hxDR[0, :]).flatten(),
195+
np.array(hxDR[1, :]).flatten(), "-k")
196+
plt.plot(np.array(hxEst[0, :]).flatten(),
197+
np.array(hxEst[1, :]).flatten(), "-r")
198+
plt.axis("equal")
199+
plt.grid(True)
200+
plt.pause(0.001)
201+
202+
203+
if __name__ == '__main__':
204+
main()

0 commit comments

Comments
 (0)