mirror of
https://github.com/AtsushiSakai/PythonRobotics.git
synced 2026-01-13 14:48:02 -05:00
improve code
This commit is contained in:
@@ -12,11 +12,15 @@
|
||||
import random
|
||||
import math
|
||||
import copy
|
||||
import pandas as pd
|
||||
import numpy as np
|
||||
import reeds_shepp_path_planning
|
||||
import pure_pursuit
|
||||
import unicycle_model
|
||||
import pandas as pd
|
||||
|
||||
|
||||
target_speed = 10.0 / 3.6
|
||||
accel = 0.1
|
||||
curvature = 10.0
|
||||
|
||||
|
||||
class RRT():
|
||||
@@ -82,7 +86,7 @@ class RRT():
|
||||
print("feasible path is found")
|
||||
break
|
||||
|
||||
return x, y, yaw, v, t, a, d
|
||||
return flag, x, y, yaw, v, t, a, d
|
||||
|
||||
def calc_tracking_path(self, path):
|
||||
path = np.matrix(path[::-1])
|
||||
@@ -106,14 +110,8 @@ class RRT():
|
||||
|
||||
def check_tracking_path_is_feasible(self, path):
|
||||
print("check_tracking_path_is_feasible")
|
||||
path = np.matrix(path[::-1])
|
||||
|
||||
init_speed = 0.0
|
||||
max_speed = 10.0 / 3.6
|
||||
|
||||
path = self.calc_tracking_path(path)
|
||||
# speed_profile = self.calc_speed_profile(path, max_speed)
|
||||
|
||||
# plt.plot(path[:, 0], path[:, 1], '-xg')
|
||||
# save csv
|
||||
df = pd.DataFrame()
|
||||
df["x"] = np.array(path[:, 0]).flatten()
|
||||
@@ -121,52 +119,34 @@ class RRT():
|
||||
df["yaw"] = np.array(path[:, 2]).flatten()
|
||||
df.to_csv("rrt_course.csv", index=None)
|
||||
|
||||
state = unicycle_model.State(
|
||||
x=self.start.x, y=self.start.y, yaw=self.start.yaw, v=init_speed)
|
||||
cx = np.array(path[:, 0])
|
||||
cy = np.array(path[:, 1])
|
||||
cyaw = np.array(path[:, 2])
|
||||
|
||||
target_ind = pure_pursuit.calc_nearest_index(
|
||||
state, path[:, 0], path[:, 1])
|
||||
goal = [cx[-1], cy[-1], cyaw[-1]]
|
||||
|
||||
lastIndex = len(path[:, 0]) - 2
|
||||
cx, cy, cyaw = pure_pursuit.extend_path(cx, cy, cyaw)
|
||||
|
||||
x = [state.x]
|
||||
y = [state.y]
|
||||
yaw = [state.yaw]
|
||||
v = [state.v]
|
||||
t = [0.0]
|
||||
a = [0.0]
|
||||
d = [0.0]
|
||||
time = 0.0
|
||||
speed_profile = pure_pursuit.calc_speed_profile(
|
||||
cx, cy, cyaw, target_speed, accel)
|
||||
|
||||
while lastIndex > target_ind:
|
||||
# print(lastIndex, target_ind)
|
||||
ai = pure_pursuit.PIDControl(max_speed, state.v)
|
||||
di, target_ind = pure_pursuit.pure_pursuit_control(
|
||||
state, path[:, 0], path[:, 1], target_ind)
|
||||
state = unicycle_model.update(state, ai, di)
|
||||
t, x, y, yaw, v, a, d, find_goal = pure_pursuit.closed_loop_prediction(
|
||||
cx, cy, cyaw, speed_profile, goal)
|
||||
|
||||
time = time + unicycle_model.dt
|
||||
if abs(yaw[-1] - goal[2]) >= math.pi / 2.0:
|
||||
print(yaw[-1], goal[2])
|
||||
find_goal = False
|
||||
if not find_goal:
|
||||
print("This path is bad")
|
||||
|
||||
x.append(state.x)
|
||||
y.append(state.y)
|
||||
yaw.append(state.yaw)
|
||||
v.append(state.v)
|
||||
t.append(time)
|
||||
a.append(ai)
|
||||
d.append(di)
|
||||
plt.clf
|
||||
plt.plot(x, y, '-r')
|
||||
plt.plot(path[:, 0], path[:, 1], '-g')
|
||||
plt.grid(True)
|
||||
plt.axis("equal")
|
||||
plt.show()
|
||||
|
||||
if self.CollisionCheckWithXY(path[:, 0], path[:, 1], self.obstacleList):
|
||||
# print("OK")
|
||||
return True, x, y, yaw, v, t, a, d
|
||||
else:
|
||||
# print("NG")
|
||||
return False, x, y, yaw, v, t, a, d
|
||||
|
||||
# plt.plot(x, y, '-r')
|
||||
# plt.plot(path[:, 0], path[:, 1], '-g')
|
||||
# plt.show()
|
||||
|
||||
# return True
|
||||
return find_goal, x, y, yaw, v, t, a, d
|
||||
|
||||
def choose_parent(self, newNode, nearinds):
|
||||
if len(nearinds) == 0:
|
||||
@@ -202,7 +182,6 @@ class RRT():
|
||||
|
||||
def steer(self, rnd, nind):
|
||||
# print(rnd)
|
||||
curvature = 5.0
|
||||
|
||||
nearestNode = self.nodeList[nind]
|
||||
|
||||
@@ -313,6 +292,7 @@ class RRT():
|
||||
for node in self.nodeList:
|
||||
if node.parent is not None:
|
||||
plt.plot(node.path_x, node.path_y, "-g")
|
||||
pass
|
||||
# plt.plot([node.x, self.nodeList[node.parent].x], [
|
||||
# node.y, self.nodeList[node.parent].y], "-g")
|
||||
|
||||
@@ -401,7 +381,11 @@ if __name__ == '__main__':
|
||||
goal = [10.0, 10.0, math.radians(0.0)]
|
||||
|
||||
rrt = RRT(start, goal, randArea=[-2.0, 15.0], obstacleList=obstacleList)
|
||||
x, y, yaw, v, t, a, d = rrt.Planning(animation=False)
|
||||
flag, x, y, yaw, v, t, a, d = rrt.Planning(animation=False)
|
||||
|
||||
if not flag:
|
||||
print("cannot find feasible path")
|
||||
exit()
|
||||
|
||||
# flg, ax = plt.subplots(1)
|
||||
# Draw final path
|
||||
@@ -429,7 +413,7 @@ if __name__ == '__main__':
|
||||
flg, ax = plt.subplots(1)
|
||||
plt.plot(t, a, '-r')
|
||||
plt.xlabel("time[s]")
|
||||
plt.ylabel("input[m/s]")
|
||||
plt.ylabel("accel[m/ss]")
|
||||
plt.grid(True)
|
||||
|
||||
flg, ax = plt.subplots(1)
|
||||
|
||||
@@ -12,8 +12,14 @@ import math
|
||||
import matplotlib.pyplot as plt
|
||||
import unicycle_model
|
||||
|
||||
Kp = 1.0 # speed propotional gain
|
||||
Kp = 2.0 # speed propotional gain
|
||||
Lf = 1.0 # look-ahead distance
|
||||
T = 1000.0 # max simulation time
|
||||
goal_dis = 0.5
|
||||
stop_speed = 0.1
|
||||
|
||||
# animation = True
|
||||
animation = False
|
||||
|
||||
|
||||
def PIDControl(target, current):
|
||||
@@ -24,20 +30,24 @@ def PIDControl(target, current):
|
||||
|
||||
def pure_pursuit_control(state, cx, cy, pind):
|
||||
|
||||
if state.v >= 0:
|
||||
ind = calc_nearest_index(state, cx[pind:], cy[pind:])
|
||||
ind = calc_target_index(state, cx, cy)
|
||||
|
||||
if pind >= ind:
|
||||
ind = pind
|
||||
|
||||
# print(pind, ind)
|
||||
if ind < len(cx):
|
||||
tx = cx[ind]
|
||||
ty = cy[ind]
|
||||
else:
|
||||
ind = calc_nearest_index(state, cx[:pind + 1], cy[:pind + 1])
|
||||
|
||||
if state.v >= 0:
|
||||
ind = ind + pind
|
||||
|
||||
tx = cx[ind]
|
||||
ty = cy[ind]
|
||||
tx = cx[-1]
|
||||
ty = cy[-1]
|
||||
ind = len(cx) - 1
|
||||
|
||||
alpha = math.atan2(ty - state.y, tx - state.x) - state.yaw
|
||||
|
||||
if state.v < 0: # back
|
||||
if state.v <= 0.0: # back
|
||||
# alpha = math.pi - alpha
|
||||
if alpha > 0:
|
||||
alpha = math.pi - alpha
|
||||
else:
|
||||
@@ -45,33 +55,195 @@ def pure_pursuit_control(state, cx, cy, pind):
|
||||
|
||||
delta = math.atan2(2.0 * unicycle_model.L * math.sin(alpha) / Lf, 1.0)
|
||||
|
||||
if state.v < 0: # back
|
||||
delta = delta * -1.0
|
||||
|
||||
return delta, ind
|
||||
|
||||
|
||||
def calc_nearest_index(state, cx, cy):
|
||||
def calc_target_index(state, cx, cy):
|
||||
dx = [state.x - icx for icx in cx]
|
||||
dy = [state.y - icy for icy in cy]
|
||||
|
||||
d = [abs(math.sqrt(idx ** 2 + idy ** 2) -
|
||||
Lf) for (idx, idy) in zip(dx, dy)]
|
||||
d = [abs(math.sqrt(idx ** 2 + idy ** 2)) for (idx, idy) in zip(dx, dy)]
|
||||
|
||||
ind = d.index(min(d))
|
||||
|
||||
L = 0.0
|
||||
|
||||
while Lf > L and (ind + 1) < len(cx):
|
||||
dx = cx[ind + 1] - cx[ind]
|
||||
dy = cx[ind + 1] - cx[ind]
|
||||
L += math.sqrt(dx ** 2 + dy ** 2)
|
||||
ind += 1
|
||||
|
||||
return ind
|
||||
|
||||
|
||||
def closed_loop_prediction(cx, cy, cyaw, speed_profile, goal):
|
||||
|
||||
state = unicycle_model.State(x=-0.0, y=-0.0, yaw=0.0, v=0.0)
|
||||
|
||||
# lastIndex = len(cx) - 1
|
||||
time = 0.0
|
||||
x = [state.x]
|
||||
y = [state.y]
|
||||
yaw = [state.yaw]
|
||||
v = [state.v]
|
||||
t = [0.0]
|
||||
a = [0.0]
|
||||
d = [0.0]
|
||||
target_ind = calc_target_index(state, cx, cy)
|
||||
find_goal = False
|
||||
|
||||
while T >= time:
|
||||
di, target_ind = pure_pursuit_control(state, cx, cy, target_ind)
|
||||
ai = PIDControl(speed_profile[target_ind], state.v)
|
||||
state = unicycle_model.update(state, ai, di)
|
||||
|
||||
if abs(state.v) <= stop_speed:
|
||||
target_ind += 1
|
||||
|
||||
time = time + unicycle_model.dt
|
||||
|
||||
# check goal
|
||||
dx = state.x - goal[0]
|
||||
dy = state.y - goal[1]
|
||||
if math.sqrt(dx ** 2 + dy ** 2) <= goal_dis:
|
||||
find_goal = True
|
||||
break
|
||||
|
||||
x.append(state.x)
|
||||
y.append(state.y)
|
||||
yaw.append(state.yaw)
|
||||
v.append(state.v)
|
||||
t.append(time)
|
||||
a.append(ai)
|
||||
d.append(di)
|
||||
|
||||
if target_ind % 20 == 0 and animation:
|
||||
plt.cla()
|
||||
plt.plot(cx, cy, "-r", label="course")
|
||||
plt.plot(x, y, "ob", label="trajectory")
|
||||
plt.plot(cx[target_ind], cy[target_ind], "xg", label="target")
|
||||
plt.axis("equal")
|
||||
plt.grid(True)
|
||||
plt.title("speed:" + str(round(state.v, 2)) +
|
||||
"tind:" + str(target_ind))
|
||||
plt.pause(0.0001)
|
||||
|
||||
return t, x, y, yaw, v, a, d, find_goal
|
||||
|
||||
|
||||
def set_stop_point(target_speed, cx, cy, cyaw):
|
||||
speed_profile = [target_speed] * len(cx)
|
||||
forward = True
|
||||
|
||||
d = []
|
||||
|
||||
# Set stop point
|
||||
for i in range(len(cx) - 1):
|
||||
dx = cx[i + 1] - cx[i]
|
||||
dy = cy[i + 1] - cy[i]
|
||||
d.append(math.sqrt(dx ** 2.0 + dy ** 2.0))
|
||||
iyaw = cyaw[i]
|
||||
move_direction = math.atan2(dy, dx)
|
||||
is_back = abs(move_direction - iyaw) >= math.pi / 2.0
|
||||
|
||||
if dx == 0.0 and dy == 0.0:
|
||||
continue
|
||||
|
||||
if is_back:
|
||||
speed_profile[i] = - target_speed
|
||||
else:
|
||||
speed_profile[i] = target_speed
|
||||
|
||||
if is_back and forward:
|
||||
speed_profile[i] = 0.0
|
||||
forward = False
|
||||
# plt.plot(cx[i], cy[i], "xb")
|
||||
# print(iyaw, move_direction, dx, dy)
|
||||
elif not is_back and not forward:
|
||||
speed_profile[i] = 0.0
|
||||
forward = True
|
||||
# plt.plot(cx[i], cy[i], "xb")
|
||||
# print(iyaw, move_direction, dx, dy)
|
||||
speed_profile[0] = 0.0
|
||||
speed_profile[-1] = 0.0
|
||||
|
||||
d.append(d[-1])
|
||||
|
||||
return speed_profile, d
|
||||
|
||||
|
||||
def calc_speed_profile(cx, cy, cyaw, target_speed, a):
|
||||
|
||||
speed_profile, d = set_stop_point(target_speed, cx, cy, cyaw)
|
||||
|
||||
nsp = len(speed_profile)
|
||||
|
||||
if animation:
|
||||
plt.plot(speed_profile, "xb")
|
||||
|
||||
# forward integration
|
||||
for i in range(nsp - 1):
|
||||
|
||||
if speed_profile[i + 1] >= 0: # forward
|
||||
tspeed = speed_profile[i] + a * d[i]
|
||||
if tspeed <= speed_profile[i + 1]:
|
||||
speed_profile[i + 1] = tspeed
|
||||
else:
|
||||
tspeed = speed_profile[i] - a * d[i]
|
||||
if tspeed >= speed_profile[i + 1]:
|
||||
speed_profile[i + 1] = tspeed
|
||||
|
||||
if animation:
|
||||
plt.plot(speed_profile, "ok")
|
||||
|
||||
# back integration
|
||||
for i in range(nsp - 1):
|
||||
if speed_profile[- i - 1] >= 0: # forward
|
||||
tspeed = speed_profile[-i] + a * d[-i]
|
||||
if tspeed <= speed_profile[-i - 1]:
|
||||
speed_profile[-i - 1] = tspeed
|
||||
else:
|
||||
tspeed = speed_profile[-i] - a * d[-i]
|
||||
if tspeed >= speed_profile[-i - 1]:
|
||||
speed_profile[-i - 1] = tspeed
|
||||
|
||||
if animation:
|
||||
plt.plot(speed_profile, "-r")
|
||||
plt.show()
|
||||
|
||||
return speed_profile
|
||||
|
||||
|
||||
def extend_path(cx, cy, cyaw):
|
||||
|
||||
dl = 0.1
|
||||
dl_list = [dl] * (int(Lf / dl) + 10)
|
||||
|
||||
move_direction = math.atan2(cy[-1] - cy[-2], cx[-1] - cx[-2])
|
||||
is_back = abs(move_direction - cyaw[-1]) >= math.pi / 2.0
|
||||
|
||||
for idl in dl_list:
|
||||
if is_back:
|
||||
idl *= -1
|
||||
cx = np.append(cx, cx[-1] + idl * math.cos(cyaw[-1]))
|
||||
cy = np.append(cy, cy[-1] + idl * math.sin(cyaw[-1]))
|
||||
cyaw = np.append(cyaw, cyaw[-1])
|
||||
|
||||
return cx, cy, cyaw
|
||||
|
||||
|
||||
def main():
|
||||
# target course
|
||||
# target course
|
||||
import numpy as np
|
||||
cx = np.arange(0, 50, 0.1)
|
||||
cy = [math.sin(ix / 5.0) * ix / 2.0 for ix in cx]
|
||||
target_speed = 30.0 / 3.6
|
||||
|
||||
target_speed = 5.0 / 3.6
|
||||
|
||||
T = 15.0 # max simulation time
|
||||
|
||||
state = unicycle_model.State(x=-1.0, y=-5.0, yaw=0.0, v=0.0)
|
||||
state = unicycle_model.State(x=-0.0, y=-3.0, yaw=0.0, v=0.0)
|
||||
# state = unicycle_model.State(x=-1.0, y=-5.0, yaw=0.0, v=-30.0 / 3.6)
|
||||
# state = unicycle_model.State(x=10.0, y=5.0, yaw=0.0, v=-30.0 / 3.6)
|
||||
# state = unicycle_model.State(
|
||||
@@ -86,7 +258,7 @@ def main():
|
||||
yaw = [state.yaw]
|
||||
v = [state.v]
|
||||
t = [0.0]
|
||||
target_ind = calc_nearest_index(state, cx, cy)
|
||||
target_ind = calc_target_index(state, cx, cy)
|
||||
|
||||
while T >= time and lastIndex > target_ind:
|
||||
ai = PIDControl(target_speed, state.v)
|
||||
@@ -127,6 +299,44 @@ def main():
|
||||
plt.show()
|
||||
|
||||
|
||||
def main2():
|
||||
import pandas as pd
|
||||
data = pd.read_csv("rrt_course.csv")
|
||||
cx = np.array(data["x"])
|
||||
cy = np.array(data["y"])
|
||||
cyaw = np.array(data["yaw"])
|
||||
|
||||
target_speed = 10.0 / 3.6
|
||||
a = 2.0
|
||||
|
||||
goal = [cx[-1], cy[-1]]
|
||||
|
||||
cx, cy, cyaw = extend_path(cx, cy, cyaw)
|
||||
|
||||
speed_profile = calc_speed_profile(cx, cy, cyaw, target_speed, a)
|
||||
|
||||
t, x, y, yaw, v, a, d, flag = closed_loop_prediction(
|
||||
cx, cy, cyaw, speed_profile, goal)
|
||||
|
||||
flg, ax = plt.subplots(1)
|
||||
plt.plot(cx, cy, ".r", label="course")
|
||||
plt.plot(x, y, "-b", label="trajectory")
|
||||
plt.plot(goal[0], goal[1], "xg", label="goal")
|
||||
plt.legend()
|
||||
plt.xlabel("x[m]")
|
||||
plt.ylabel("y[m]")
|
||||
plt.axis("equal")
|
||||
plt.grid(True)
|
||||
|
||||
flg, ax = plt.subplots(1)
|
||||
plt.plot(t, [iv * 3.6 for iv in v], "-r")
|
||||
plt.xlabel("Time[s]")
|
||||
plt.ylabel("Speed[km/h]")
|
||||
plt.grid(True)
|
||||
plt.show()
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
print("Pure pursuit path tracking simulation start")
|
||||
main()
|
||||
# main()
|
||||
main2()
|
||||
|
||||
Reference in New Issue
Block a user