Skip to content

Commit ef39fc2

Browse files
authored
Merge pull request AtsushiSakai#299 from AtsushiSakai/issue_298
To fix pure pursuit bug AtsushiSakai#298
2 parents e8ffc01 + 2e188f8 commit ef39fc2

File tree

1 file changed

+43
-40
lines changed

1 file changed

+43
-40
lines changed

PathTracking/pure_pursuit/pure_pursuit.py

Lines changed: 43 additions & 40 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
"""
22
3-
Path tracking simulation with pure pursuit steering control and PID speed control.
3+
Path tracking simulation with pure pursuit steering and PID speed control.
44
55
author: Atsushi Sakai (@Atsushi_twi)
66
Guillaume Jacquenot (@Gjacquenot)
@@ -10,13 +10,12 @@
1010
import math
1111
import matplotlib.pyplot as plt
1212

13-
13+
# Parameters
1414
k = 0.1 # look forward gain
15-
Lfc = 2.0 # look-ahead distance
15+
Lfc = 2.0 # [m] look-ahead distance
1616
Kp = 1.0 # speed proportional gain
17-
dt = 0.1 # [s]
18-
L = 2.9 # [m] wheel base of vehicle
19-
17+
dt = 0.1 # [s] time tick
18+
WB = 2.9 # [m] wheel base of vehicle
2019

2120
show_animation = True
2221

@@ -28,20 +27,18 @@ def __init__(self, x=0.0, y=0.0, yaw=0.0, v=0.0):
2827
self.y = y
2928
self.yaw = yaw
3029
self.v = v
31-
self.rear_x = self.x - ((L / 2) * math.cos(self.yaw))
32-
self.rear_y = self.y - ((L / 2) * math.sin(self.yaw))
30+
self.rear_x = self.x - ((WB / 2) * math.cos(self.yaw))
31+
self.rear_y = self.y - ((WB / 2) * math.sin(self.yaw))
3332

3433
def update(self, a, delta):
35-
3634
self.x += self.v * math.cos(self.yaw) * dt
3735
self.y += self.v * math.sin(self.yaw) * dt
38-
self.yaw += self.v / L * math.tan(delta) * dt
36+
self.yaw += self.v / WB * math.tan(delta) * dt
3937
self.v += a * dt
40-
self.rear_x = self.x - ((L / 2) * math.cos(self.yaw))
41-
self.rear_y = self.y - ((L / 2) * math.sin(self.yaw))
38+
self.rear_x = self.x - ((WB / 2) * math.cos(self.yaw))
39+
self.rear_y = self.y - ((WB / 2) * math.sin(self.yaw))
4240

4341
def calc_distance(self, point_x, point_y):
44-
4542
dx = self.rear_x - point_x
4643
dy = self.rear_y - point_y
4744
return math.hypot(dx, dy)
@@ -56,27 +53,30 @@ def __init__(self):
5653
self.v = []
5754
self.t = []
5855

59-
def append(self, t , state):
56+
def append(self, t, state):
6057
self.x.append(state.x)
6158
self.y.append(state.y)
6259
self.yaw.append(state.yaw)
6360
self.v.append(state.v)
6461
self.t.append(t)
6562

6663

67-
def PIDControl(target, current):
64+
def proportional_control(target, current):
6865
a = Kp * (target - current)
6966

7067
return a
7168

7269

73-
class Trajectory:
70+
class TargetCourse:
71+
7472
def __init__(self, cx, cy):
7573
self.cx = cx
7674
self.cy = cy
7775
self.old_nearest_point_index = None
7876

7977
def search_target_index(self, state):
78+
79+
# To speed up nearest point search, doing it at only first time.
8080
if self.old_nearest_point_index is None:
8181
# search nearest point index
8282
dx = [state.rear_x - icx for icx in self.cx]
@@ -86,47 +86,45 @@ def search_target_index(self, state):
8686
self.old_nearest_point_index = ind
8787
else:
8888
ind = self.old_nearest_point_index
89-
distance_this_index = state.calc_distance(self.cx[ind], self.cy[ind])
89+
distance_this_index = state.calc_distance(self.cx[ind],
90+
self.cy[ind])
9091
while True:
91-
ind = ind + 1 if (ind + 1) < len(self.cx) else ind
92-
distance_next_index = state.calc_distance(self.cx[ind], self.cy[ind])
92+
distance_next_index = state.calc_distance(self.cx[ind + 1],
93+
self.cy[ind + 1])
9394
if distance_this_index < distance_next_index:
9495
break
96+
ind = ind + 1 if (ind + 1) < len(self.cx) else ind
9597
distance_this_index = distance_next_index
9698
self.old_nearest_point_index = ind
9799

98-
L = 0.0
99-
100-
Lf = k * state.v + Lfc
100+
Lf = k * state.v + Lfc # update look ahead distance
101101

102102
# search look ahead target point index
103-
while Lf > L and (ind + 1) < len(self.cx):
104-
L = state.calc_distance(self.cx[ind], self.cy[ind])
103+
while Lf > state.calc_distance(self.cx[ind], self.cy[ind]):
104+
if (ind + 1) >= len(self.cx):
105+
break # not exceed goal
105106
ind += 1
106107

107-
return ind
108+
return ind, Lf
108109

109110

110-
def pure_pursuit_control(state, trajectory, pind):
111-
112-
ind = trajectory.search_target_index(state)
111+
def pure_pursuit_steer_control(state, trajectory, pind):
112+
ind, Lf = trajectory.search_target_index(state)
113113

114114
if pind >= ind:
115115
ind = pind
116116

117117
if ind < len(trajectory.cx):
118118
tx = trajectory.cx[ind]
119119
ty = trajectory.cy[ind]
120-
else:
120+
else: # toward goal
121121
tx = trajectory.cx[-1]
122122
ty = trajectory.cy[-1]
123123
ind = len(trajectory.cx) - 1
124124

125125
alpha = math.atan2(ty - state.rear_y, tx - state.rear_x) - state.yaw
126126

127-
Lf = k * state.v + Lfc
128-
129-
delta = math.atan2(2.0 * L * math.sin(alpha) / Lf, 1.0)
127+
delta = math.atan2(2.0 * WB * math.sin(alpha) / Lf, 1.0)
130128

131129
return delta, ind
132130

@@ -147,7 +145,7 @@ def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", ec="k"):
147145

148146
def main():
149147
# target course
150-
cx = np.arange(0, 50, 0.1)
148+
cx = np.arange(0, 50, 0.5)
151149
cy = [math.sin(ix / 5.0) * ix / 2.0 for ix in cx]
152150

153151
target_speed = 10.0 / 3.6 # [m/s]
@@ -161,22 +159,27 @@ def main():
161159
time = 0.0
162160
states = States()
163161
states.append(time, state)
164-
trajectory = Trajectory(cx, cy)
165-
target_ind = trajectory.search_target_index(state)
162+
target_course = TargetCourse(cx, cy)
163+
target_ind, _ = target_course.search_target_index(state)
166164

167165
while T >= time and lastIndex > target_ind:
168-
ai = PIDControl(target_speed, state.v)
169-
di, target_ind = pure_pursuit_control(state, trajectory, target_ind)
170-
state.update(ai, di)
166+
167+
# Calc control input
168+
ai = proportional_control(target_speed, state.v)
169+
di, target_ind = pure_pursuit_steer_control(
170+
state, target_course, target_ind)
171+
172+
state.update(ai, di) # Control vehicle
171173

172174
time += dt
173175
states.append(time, state)
174176

175177
if show_animation: # pragma: no cover
176178
plt.cla()
177179
# for stopping simulation with the esc key.
178-
plt.gcf().canvas.mpl_connect('key_release_event',
179-
lambda event: [exit(0) if event.key == 'escape' else None])
180+
plt.gcf().canvas.mpl_connect(
181+
'key_release_event',
182+
lambda event: [exit(0) if event.key == 'escape' else None])
180183
plot_arrow(state.x, state.y, state.yaw)
181184
plt.plot(cx, cy, "-r", label="course")
182185
plt.plot(states.x, states.y, "-b", label="trajectory")

0 commit comments

Comments
 (0)