-
Notifications
You must be signed in to change notification settings - Fork 4
/
Copy pathlqr_speed_steer_control.py
executable file
·260 lines (185 loc) · 6.11 KB
/
lqr_speed_steer_control.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
# -*- coding: utf-8 -*-
"""
Path tracking simulation with LQR speed and steering control
author Atsushi Sakai (@Atsushi_twi)
"""
import numpy as np
import math
import matplotlib.pyplot as plt
import scipy.linalg as la
# LQR parameter
Q = np.diag([3,3,4,4,1])
R = np.diag([3,1])
# parameters
dt = 0.1 # time tick[s]
L = 0.5 # Wheel base of the vehicle [m]
max_steer = math.radians(45.0) # maximum steering angle[rad]
show_animation = True
class State:
def __init__(self, x=0.0, y=0.0, yaw=0.0, v=0.0):
self.x = x
self.y = y
self.yaw = yaw
self.v = v
def update(state, a, delta):
if delta >= max_steer:
delta = max_steer
if delta <= - max_steer:
delta = - max_steer
state.x = state.x + state.v * math.cos(state.yaw) * dt
state.y = state.y + state.v * math.sin(state.yaw) * dt
state.yaw = state.yaw + state.v / L * math.tan(delta) * dt
state.v = state.v + a * dt
return state
def pi_2_pi(angle):
return (angle + math.pi) % (2*math.pi) - math.pi #将角度 从(0,2pi) 转换为 (-pi,pi)
def solve_DARE(A, B, Q, R):
"""
solve a discrete time_Algebraic Riccati equation (DARE)
"""
X = Q
maxiter = 150
eps = 0.01
for i in range(maxiter):
Xn = A.T * X * A - A.T * X * B * \
la.inv(R + B.T * X * B) * B.T * X * A + Q
if (abs(Xn - X)).max() < eps:
X = Xn
break
X = Xn
return Xn
def dlqr(A, B, Q, R):
"""Solve the discrete time lqr controller.
x[k+1] = A x[k] + B u[k]
cost = sum x[k].T*Q*x[k] + u[k].T*R*u[k]
# ref Bertsekas, p.151
"""
# first, try to solve the ricatti equation
X = solve_DARE(A, B, Q, R)
# compute the LQR gain
K = np.matrix(la.inv(B.T * X * B + R) * (B.T * X * A))
eigVals, eigVecs = la.eig(A - B * K)
return K, X, eigVals
def lqr_steering_control(cx, cy, cyaw, e, th_e, pe, pth_e, sp):
#ind, e = calc_nearest_index(state, cx, cy, cyaw)# ind是得到的最近点的下标,e是最近点与当前点的距离误差
tv = sp #不修改速度,这里设置当前速度和目标速度一致
v = sp
dt = 0.1 # 单位时间 0.1s
L = 1 # 车长 [m]
th_e = pi_2_pi(th_e) #th_e 是当前车的航向角误差,然后转换到了(-pi,pi)范围内
# LQR parameter
Q = np.eye(5)
R = np.eye(2)
A = np.matrix(np.zeros((5, 5)))
A[0, 0] = 1.0
A[0, 1] = dt
A[1, 2] = v
A[2, 2] = 1.0
A[2, 3] = dt
A[4, 4] = 1.0
B = np.matrix(np.zeros((5, 2)))
B[3, 0] = v / L
B[4, 1] = dt
K, _, _ = dlqr(A, B, Q, R) #求解K矩阵
x = np.matrix(np.zeros((5, 1))) #状态变量参数定义
x[0, 0] = e
x[1, 0] = (e - pe) / dt
x[2, 0] = th_e
x[3, 0] = (th_e - pth_e) / dt
x[4, 0] = v - tv
ustar = -K * x #利用求好的K矩阵,通过状态变量得到控制变量
# calc steering input
#ff = math.atan2(L * k, 1)
fb = pi_2_pi(ustar[0, 0])
#delta = ff + fb
delta = fb
# calc accel input
a = ustar[1, 0]
return delta, a, e, th_e
def calc_nearest_index(state, cx, cy, cyaw):
dx = [state.x - icx for icx in cx]
dy = [state.y - icy for icy in cy]
d = [idx ** 2 + idy ** 2 for (idx, idy) in zip(dx, dy)]
mind = min(d)
ind = d.index(mind)
mind = math.sqrt(mind)
dxl = cx[ind] - state.x
dyl = cy[ind] - state.y
angle = pi_2_pi(cyaw[ind] - math.atan2(dyl, dxl))
if angle < 0:
mind *= -1
return ind, mind
def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal):
T = 500.0 # max simulation time
goal_dis = 0.3
stop_speed = 0.05
state = State(x=-0.0, y=-0.0, yaw=0.0, v=0.0)
time = 0.0
x = [state.x]
y = [state.y]
yaw = [state.yaw]
v = [state.v]
t = [0.0]
target_ind = calc_nearest_index(state, cx, cy, cyaw)
e, e_th = 0.0, 0.0
while T >= time:
dl, target_ind, e, e_th, ai = lqr_steering_control(state, cx, cy, cyaw, ck, e, e_th, speed_profile)
state = update(state, ai, dl)
if abs(state.v) <= stop_speed:
target_ind += 1
time = time + dt
# check goal
dx = state.x - goal[0]
dy = state.y - goal[1]
if math.sqrt(dx ** 2 + dy ** 2) <= goal_dis:
print("Goal")
break
x.append(state.x)
y.append(state.y)
yaw.append(state.yaw)
v.append(state.v)
t.append(time)
if target_ind % 1 == 0 and show_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[km/h]:" + str(round(state.v * 3.6, 2)) +
",target index:" + str(target_ind))
plt.pause(0.0001)
return t, x, y, yaw, v
def calc_speed_profile(cx, cy, cyaw, target_speed):
speed_profile = [target_speed] * len(cx)
direction = 1.0
# Set stop point
for i in range(len(cx) - 1):
dyaw = abs(cyaw[i + 1] - cyaw[i])
switch = math.pi / 4.0 <= dyaw < math.pi / 2.0
if switch:
direction *= -1
if direction != 1.0:
speed_profile[i] = - target_speed
else:
speed_profile[i] = target_speed
if switch:
speed_profile[i] = 0.0
# speed down
for i in range(40):
speed_profile[-i] = target_speed / (50 - i)
if speed_profile[-i] <= 1.0 / 3.6:
speed_profile[-i] = 1.0 / 3.6
return speed_profile
def main():
print("LQR steering control tracking start!!")
ax = [0.0, 6.0, 12.5, 10.0, 17.5, 20.0, 25.0]
ay = [0.0, -3.0, -5.0, 6.5, 3.0, 0.0, 0.0]
goal = [ax[-1], ay[-1]]
cx, cy, cyaw, ck, s = cubic_spline_planner.calc_spline_course(
ax, ay, ds=0.1)
target_speed = 10.0 / 3.6 # simulation parameter km/h -> m/s
sp = calc_speed_profile(cx, cy, cyaw, target_speed)
t, x, y, yaw, v = closed_loop_prediction(cx, cy, cyaw, ck, sp, goal)
if __name__ == '__main__':
main()