1313import scipy .linalg as la
1414
1515sys .path .append ("../../PathPlanning/CubicSpline/" )
16- import cubic_spline_planner
1716
17+ try :
18+ import cubic_spline_planner
19+ except ImportError :
20+ raise
1821
19- # LQR parameter
20- Q = np .eye (5 )
21- R = np .eye (2 )
22+ # === Parameters =====
2223
23- # parameters
24+ # LQR parameter
25+ lqr_Q = np .eye (5 )
26+ lqr_R = np .eye (2 )
2427dt = 0.1 # time tick[s]
2528L = 0.5 # Wheel base of the vehicle [m]
2629max_steer = np .deg2rad (45.0 ) # maximum steering angle[rad]
@@ -56,23 +59,23 @@ def pi_2_pi(angle):
5659 return (angle + math .pi ) % (2 * math .pi ) - math .pi
5760
5861
59- def solve_DARE (A , B , Q , R ):
62+ def solve_dare (A , B , Q , R ):
6063 """
6164 solve a discrete time_Algebraic Riccati equation (DARE)
6265 """
63- X = Q
64- Xn = Q
65- maxiter = 150
66+ x = Q
67+ x_next = Q
68+ max_iter = 150
6669 eps = 0.01
6770
68- for i in range (maxiter ):
69- Xn = A .T @ X @ A - A .T @ X @ B @ \
70- la .inv (R + B .T @ X @ B ) @ B .T @ X @ A + Q
71- if (abs (Xn - X )).max () < eps :
71+ for i in range (max_iter ):
72+ x_next = A .T @ x @ A - A .T @ x @ B @ \
73+ la .inv (R + B .T @ x @ B ) @ B .T @ x @ A + Q
74+ if (abs (x_next - x )).max () < eps :
7275 break
73- X = Xn
76+ x = x_next
7477
75- return Xn
78+ return x_next
7679
7780
7881def dlqr (A , B , Q , R ):
@@ -83,17 +86,17 @@ def dlqr(A, B, Q, R):
8386 """
8487
8588 # first, try to solve the ricatti equation
86- X = solve_DARE (A , B , Q , R )
89+ X = solve_dare (A , B , Q , R )
8790
8891 # compute the LQR gain
8992 K = la .inv (B .T @ X @ B + R ) @ (B .T @ X @ A )
9093
91- eigs = la .eig (A - B @ K )
94+ eig_result = la .eig (A - B @ K )
9295
93- return K , X , eigs [0 ]
96+ return K , X , eig_result [0 ]
9497
9598
96- def lqr_steering_control (state , cx , cy , cyaw , ck , pe , pth_e , sp ):
99+ def lqr_speed_steering_control (state , cx , cy , cyaw , ck , pe , pth_e , sp , Q , R ):
97100 ind , e = calc_nearest_index (state , cx , cy , cyaw )
98101
99102 tv = sp [ind ]
@@ -102,42 +105,59 @@ def lqr_steering_control(state, cx, cy, cyaw, ck, pe, pth_e, sp):
102105 v = state .v
103106 th_e = pi_2_pi (state .yaw - cyaw [ind ])
104107
108+ # A = [1.0, dt, 0.0, 0.0, 0.0
109+ # 0.0, 0.0, v, 0.0, 0.0]
110+ # 0.0, 0.0, 1.0, dt, 0.0]
111+ # 0.0, 0.0, 0.0, 0.0, 0.0]
112+ # 0.0, 0.0, 0.0, 0.0, 1.0]
105113 A = np .zeros ((5 , 5 ))
106114 A [0 , 0 ] = 1.0
107115 A [0 , 1 ] = dt
108116 A [1 , 2 ] = v
109117 A [2 , 2 ] = 1.0
110118 A [2 , 3 ] = dt
111119 A [4 , 4 ] = 1.0
112- # print(A)
113120
121+ # B = [0.0, 0.0
122+ # 0.0, 0.0
123+ # 0.0, 0.0
124+ # v/L, 0.0
125+ # 0.0, dt]
114126 B = np .zeros ((5 , 2 ))
115127 B [3 , 0 ] = v / L
116128 B [4 , 1 ] = dt
117129
118130 K , _ , _ = dlqr (A , B , Q , R )
119131
132+ # state vector
133+ # x = [e, dot_e, th_e, dot_th_e, delta_v]
134+ # e: lateral distance to the path
135+ # dot_e: derivative of e
136+ # th_e: angle difference to the path
137+ # dot_th_e: derivative of th_e
138+ # delta_v: difference between current speed and target speed
120139 x = np .zeros ((5 , 1 ))
121-
122140 x [0 , 0 ] = e
123141 x [1 , 0 ] = (e - pe ) / dt
124142 x [2 , 0 ] = th_e
125143 x [3 , 0 ] = (th_e - pth_e ) / dt
126144 x [4 , 0 ] = v - tv
127145
146+ # input vector
147+ # u = [delta, accel]
148+ # delta: steering angle
149+ # accel: acceleration
128150 ustar = - K @ x
129151
130152 # calc steering input
131-
132- ff = math . atan2 ( L * k , 1 )
133- fb = pi_2_pi ( ustar [ 0 , 0 ])
153+ ff = math . atan2 ( L * k , 1 ) # feedforward steering angle
154+ fb = pi_2_pi ( ustar [ 0 , 0 ]) # feedback steering angle
155+ delta = ff + fb
134156
135157 # calc accel input
136- ai = ustar [1 , 0 ]
137-
138- delta = ff + fb
158+ accel = ustar [1 , 0 ]
139159
140- return delta , ind , e , th_e , ai
160+ return delta , ind , e , th_e , accel
141161
142162
143163def calc_nearest_index (state , cx , cy , cyaw ):
@@ -162,7 +182,7 @@ def calc_nearest_index(state, cx, cy, cyaw):
162182 return ind , mind
163183
164184
165- def closed_loop_prediction (cx , cy , cyaw , ck , speed_profile , goal ):
185+ def do_simulation (cx , cy , cyaw , ck , speed_profile , goal ):
166186 T = 500.0 # max simulation time
167187 goal_dis = 0.3
168188 stop_speed = 0.05
@@ -179,8 +199,8 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal):
179199 e , e_th = 0.0 , 0.0
180200
181201 while T >= time :
182- dl , target_ind , e , e_th , ai = lqr_steering_control (
183- state , cx , cy , cyaw , ck , e , e_th , speed_profile )
202+ dl , target_ind , e , e_th , ai = lqr_speed_steering_control (
203+ state , cx , cy , cyaw , ck , e , e_th , speed_profile , lqr_Q , lqr_R )
184204
185205 state = update (state , ai , dl )
186206
@@ -216,13 +236,13 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal):
216236 return t , x , y , yaw , v
217237
218238
219- def calc_speed_profile (cx , cy , cyaw , target_speed ):
220- speed_profile = [target_speed ] * len (cx )
239+ def calc_speed_profile (cyaw , target_speed ):
240+ speed_profile = [target_speed ] * len (cyaw )
221241
222242 direction = 1.0
223243
224244 # Set stop point
225- for i in range (len (cx ) - 1 ):
245+ for i in range (len (cyaw ) - 1 ):
226246 dyaw = abs (cyaw [i + 1 ] - cyaw [i ])
227247 switch = math .pi / 4.0 <= dyaw < math .pi / 2.0
228248
@@ -256,9 +276,9 @@ def main():
256276 ax , ay , ds = 0.1 )
257277 target_speed = 10.0 / 3.6 # simulation parameter km/h -> m/s
258278
259- sp = calc_speed_profile (cx , cy , cyaw , target_speed )
279+ sp = calc_speed_profile (cyaw , target_speed )
260280
261- t , x , y , yaw , v = closed_loop_prediction (cx , cy , cyaw , ck , sp , goal )
281+ t , x , y , yaw , v = do_simulation (cx , cy , cyaw , ck , sp , goal )
262282
263283 if show_animation : # pragma: no cover
264284 plt .close ()
0 commit comments