Skip to content

Commit 5b033b2

Browse files
committed
add lqr steering sample
1 parent bee232e commit 5b033b2

File tree

3 files changed

+23
-42
lines changed

3 files changed

+23
-42
lines changed

PathTracking/lqr/animation.gif

3.25 MB
Loading

PathTracking/lqr/lqr_tracking.py

Lines changed: 15 additions & 41 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
#! /usr/bin/python
22
"""
33
4-
Path tracking simulation with rear wheel feedback steering control and PID speed control.
4+
Path tracking simulation with LQR steering control and PID speed control.
55
66
author: Atsushi Sakai
77
@@ -14,18 +14,16 @@
1414
from matplotrecorder import matplotrecorder
1515
import scipy.linalg as la
1616

17-
Kp = 1.0 # speed propotional gain
18-
# steering control parameter
19-
KTH = 1.0
20-
KE = 0.5
17+
Kp = 1.0 # speed proportional gain
2118

19+
# LQR parameter
2220
Q = np.eye(4)
2321
R = np.eye(1)
2422

2523
animation = True
2624
# animation = False
2725

28-
matplotrecorder.donothing = True
26+
#matplotrecorder.donothing = True
2927

3028

3129
def PIDControl(target, current):
@@ -81,26 +79,7 @@ def dlqr(A, B, Q, R):
8179
return K, X, eigVals
8280

8381

84-
def rear_wheel_feedback_control(state, cx, cy, cyaw, ck, preind):
85-
ind, e = calc_nearest_index(state, cx, cy, cyaw)
86-
87-
k = ck[ind]
88-
v = state.v
89-
th_e = pi_2_pi(state.yaw - cyaw[ind])
90-
91-
omega = v * k * math.cos(th_e) / (1.0 - k * e) - \
92-
KTH * abs(v) * th_e - KE * v * math.sin(th_e) * e / th_e
93-
94-
if th_e == 0.0 or omega == 0.0:
95-
return 0.0, ind
96-
97-
delta = math.atan2(unicycle_model.L * omega / v, 1.0)
98-
# print(k, v, e, th_e, omega, delta)
99-
100-
return delta, ind
101-
102-
103-
def lqr_steering_control(state, cx, cy, cyaw, ck, target_ind):
82+
def lqr_steering_control(state, cx, cy, cyaw, ck, pe, pth_e):
10483
ind, e = calc_nearest_index(state, cx, cy, cyaw)
10584

10685
k = ck[ind]
@@ -123,19 +102,16 @@ def lqr_steering_control(state, cx, cy, cyaw, ck, target_ind):
123102
x = np.matrix(np.zeros((4, 1)))
124103

125104
x[0, 0] = e
126-
x[1, 0] = 0.0
105+
x[1, 0] = (e - pe)/unicycle_model.dt
127106
x[2, 0] = th_e
128-
x[3, 0] = 0.0
107+
x[3, 0] = (th_e - pth_e)/unicycle_model.dt
129108

130109
ff = math.atan2(unicycle_model.L * k, 1)
131110
fb = pi_2_pi((-K * x)[0, 0])
132-
print(math.degrees(th_e))
133-
# print(K, x)
134-
print(math.degrees(ff), math.degrees(fb))
135111

136112
delta = ff + fb
137-
# print(delta)
138-
return delta
113+
114+
return delta, ind, e, th_e
139115

140116

141117
def calc_nearest_index(state, cx, cy, cyaw):
@@ -173,12 +149,10 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal):
173149
t = [0.0]
174150
target_ind = calc_nearest_index(state, cx, cy, cyaw)
175151

176-
while T >= time:
177-
di, target_ind = rear_wheel_feedback_control(
178-
state, cx, cy, cyaw, ck, target_ind)
152+
e, e_th = 0.0, 0.0
179153

180-
dl = lqr_steering_control(state, cx, cy, cyaw, ck, target_ind)
181-
# print(di, dl)
154+
while T >= time:
155+
dl, target_ind, e, e_th = lqr_steering_control(state, cx, cy, cyaw, ck, e, e_th)
182156

183157
ai = PIDControl(speed_profile[target_ind], state.v)
184158
# state = unicycle_model.update(state, ai, di)
@@ -249,9 +223,9 @@ def calc_speed_profile(cx, cy, cyaw, target_speed):
249223

250224

251225
def main():
252-
print("rear wheel feedback tracking start!!")
253-
ax = [0.0, 6.0, 12.5, 5.0, 7.5, 3.0, -1.0]
254-
ay = [0.0, 0.0, 5.0, 6.5, 3.0, 5.0, -2.0]
226+
print("LQR steering control tracking start!!")
227+
ax = [0.0, 6.0, 12.5, 10.0, 7.5, 3.0, -1.0]
228+
ay = [0.0, -3.0, -5.0, 6.5, 3.0, 5.0, -2.0]
255229
goal = [ax[-1], ay[-1]]
256230

257231
cx, cy, cyaw, ck, s = pycubicspline.calc_spline_course(ax, ay, ds=0.1)

PathTracking/lqr/unicycle_model.py

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,8 @@
99
import math
1010

1111
dt = 0.1 # [s]
12-
L = 2.9 # [m]
12+
L = 0.5 # [m]
13+
max_steer = math.radians(45.0)
1314

1415

1516
class State:
@@ -21,6 +22,12 @@ def __init__(self, x=0.0, y=0.0, yaw=0.0, v=0.0):
2122

2223

2324
def update(state, a, delta):
25+
26+
if delta >= max_steer:
27+
delta = max_steer
28+
if delta <= - max_steer:
29+
delta = - max_steer
30+
2431
state.x = state.x + state.v * math.cos(state.yaw) * dt
2532
state.y = state.y + state.v * math.sin(state.yaw) * dt
2633
state.yaw = state.yaw + state.v / L * math.tan(delta) * dt

0 commit comments

Comments
 (0)