forked from CavalcanteM/Autonomous_Vehicle_Driving-Project
-
Notifications
You must be signed in to change notification settings - Fork 0
/
controller2d_AR.py
280 lines (236 loc) · 11.6 KB
/
controller2d_AR.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
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
#!/usr/bin/env python3
"""
2D Controller Class to be used for the CARLA waypoint follower demo.
"""
import cutils
import numpy as np
import math
class Controller2D(object):
def __init__(self, waypoints):
self.vars = cutils.CUtils()
self._current_x = 0
self._current_y = 0
self._current_yaw = 0
self._current_speed = 0
self._desired_speed = 0
self._current_frame = 0
self._current_timestamp = 0
self._start_control_loop = False
self._set_throttle = 0
self._set_brake = 0
self._set_steer = 0
self._waypoints = waypoints
self._conv_rad_to_steer = 180.0 / 70.0 / np.pi
self._pi = np.pi
self._2pi = 2.0 * np.pi
def update_values(self, x, y, yaw, speed, timestamp, frame):
self._current_x = x
self._current_y = y
self._current_yaw = yaw
self._current_speed = speed
self._current_timestamp = timestamp
self._current_frame = frame
if self._current_frame:
self._start_control_loop = True
def update_desired_speed(self):
min_idx = 0
min_dist = float("inf")
desired_speed = 0
for i in range(len(self._waypoints)):
dist = np.linalg.norm(np.array([
self._waypoints[i][0] - self._current_x,
self._waypoints[i][1] - self._current_y]))
if dist < min_dist:
min_dist = dist
min_idx = i
if min_idx < len(self._waypoints)-1:
desired_speed = self._waypoints[min_idx][2]
else:
desired_speed = self._waypoints[-1][2]
self._desired_speed = desired_speed
def update_waypoints(self, new_waypoints):
self._waypoints = new_waypoints
def get_commands(self):
return self._set_throttle, self._set_steer, self._set_brake
def set_throttle(self, input_throttle):
# Clamp the throttle command to valid bounds
throttle = np.fmax(np.fmin(input_throttle, 1.0), 0.0)
self._set_throttle = throttle
def set_steer(self, input_steer_in_rad):
# Covnert radians to [-1, 1]
input_steer = self._conv_rad_to_steer * input_steer_in_rad
# Clamp the steering command to valid bounds
steer = np.fmax(np.fmin(input_steer, 1.0), -1.0)
self._set_steer = steer
def set_brake(self, input_brake):
# Clamp the steering command to valid bounds
brake = np.fmax(np.fmin(input_brake, 1.0), 0.0)
self._set_brake = brake
def update_controls(self):
######################################################
# RETRIEVE SIMULATOR FEEDBACK
######################################################
x = self._current_x
y = self._current_y
yaw = self._current_yaw
v = self._current_speed
self.update_desired_speed()
v_desired = self._desired_speed
t = self._current_timestamp
waypoints = self._waypoints
throttle_output = 0
steer_output = 0
brake_output = 0
######################################################
######################################################
# DECLARE USAGE VARIABLES HERE
######################################################
######################################################
"""
Use 'self.vars.create_var(<variable name>, <default value>)'
to create a persistent variable (not destroyed at each iteration).
This means that the value can be stored for use in the next
iteration of the control loop.
Example: Creation of 'v_previous', default value to be 0
self.vars.create_var('v_previous', 0.0)
Example: Setting 'v_previous' to be 1.0
self.vars.v_previous = 1.0
Example: Accessing the value from 'v_previous' to be used
throttle_output = 0.5 * self.vars.v_previous
"""
self.vars.create_var('v_previous', 0.0)
self.vars.create_var('err_previous', [0.0, 0.0, 0.0]) # t, t-1, t-2
self.vars.create_var('u_previous',0.0)
# Skip the first frame to store previous values properly
if self._start_control_loop:
"""
Controller iteration code block.
Controller Feedback Variables:
x : Current X position (meters)
y : Current Y position (meters)
yaw : Current yaw pose (radians)
v : Current forward speed (meters per second)
t : Current time (seconds)
v_desired : Current desired speed (meters per second)
(Computed as the speed to track at the
closest waypoint to the vehicle.)
waypoints : Current waypoints to track
(Includes speed to track at each x,y
location.)
Format: [[x0, y0, v0],
[x1, y1, v1],
...
[xn, yn, vn]]
Example:
waypoints[2][1]:
Returns the 3rd waypoint's y position
waypoints[5]:
Returns [x5, y5, v5] (6th waypoint)
Controller Output Variables:
throttle_output : Throttle output (0 to 1)
steer_output : Steer output (-1.22 rad to 1.22 rad)
brake_output : Brake output (0 to 1)
"""
######################################################
######################################################
# IMPLEMENTATION OF LONGITUDINAL CONTROLLER HERE
######################################################
######################################################
"""
Implement a longitudinal controller here. Remember that you can
access the persistent variables declared above here. For
example, can treat self.vars.v_previous like a "global variable".
"""
######################################################
# PID CONTROL - PARAMETERS
######################################################
Ts = 0.033 # Sample time - 30FPS <-> 1/30
kp = 1.0 # Proportional Gain
ki = 0.5 # Integral Gain
kd = 0.1 # Derivative Gain
# Constants for discrete implementation
q0 = kp + (Ts * ki) + (kd / Ts)
q1 = - kp - ((2 * kd) / Ts)
q2 = kd / Ts
######################################################
# PID CONTROL - ALGORITHM
######################################################
# Errors update
self.vars.err_previous = [v_desired - v, self.vars.err_previous[0], self.vars.err_previous[1]]
# Output update
self.vars.u_previous = self.vars.u_previous + (q0 * self.vars.err_previous[0]) \
+ (q1 * self.vars.err_previous[1]) + (q2 *self.vars.err_previous[2])
if (self.vars.u_previous > 0):
throttle_output = self.vars.u_previous
brake_output = 0
else:
throttle_output = 0
brake_output = -self.vars.u_previous
######################################################
######################################################
# IMPLEMENTATION OF LATERAL CONTROLLER HERE
######################################################
######################################################
"""
Implement a lateral controller here. Remember that you can
access the persistent variables declared above here. For
example, can treat self.vars.v_previous like a "global variable".
"""
######################################################
# STANLEY CONTROL - PARAMETERS
######################################################
k_e = 1.0
k_v = 1.0
######################################################
# STANLEY CONTROL - ALGORITHM
######################################################
# Heading error
yaw_path = np.arctan2(waypoints[-1][1]-waypoints[0][1], waypoints[-1][0]-waypoints[0][0])
yaw_diff = yaw_path - yaw
# Projection of the angle in the range [-pi,pi]
if yaw_diff > np.pi:
yaw_diff -= 2 * np.pi
elif yaw_diff < - np.pi:
yaw_diff += 2 * np.pi
# Crosstrack error
current_xy = np.array([x, y])
crosstrack_error = np.min(np.sum((current_xy - np.array(waypoints)[:, :2])**2, axis=1))
# Conditions to determine the correct sign of the cross track error
yaw_cross_track = np.arctan2(y-waypoints[0][1], x-waypoints[0][0])
yaw_path2ct = yaw_path - yaw_cross_track
# Projection of the angle in the range [-pi,pi]
if yaw_path2ct > np.pi:
yaw_path2ct -= 2 * np.pi
elif yaw_path2ct < - np.pi:
yaw_path2ct += 2 * np.pi
if yaw_path2ct > 0:
crosstrack_error = abs(crosstrack_error)
else:
crosstrack_error = - abs(crosstrack_error)
yaw_diff_crosstrack = np.arctan(k_e * crosstrack_error / (k_v + v))
# Control law
steer_output = yaw_diff + yaw_diff_crosstrack
# Projection of the angle in the range [-pi,pi]
if steer_output > np.pi:
steer_output -= 2 * np.pi
elif steer_output < - np.pi:
steer_output += 2 * np.pi
steer_output = min(1.22, steer_output)
steer_output = max(-1.22, steer_output)
######################################################
# SET CONTROLS OUTPUT
######################################################
self.set_throttle(throttle_output) # in percent (0 to 1)
self.set_steer(steer_output) # in rad (-1.22 to 1.22)
self.set_brake(brake_output) # in percent (0 to 1)
######################################################
######################################################
# STORE OLD VALUES HERE (ADD MORE IF NECESSARY)
######################################################
######################################################
"""
Use this block to store old values (for example, we can store the
current x, y, and yaw values here using persistent variables for use
in the next iteration)
"""
self.vars.v_previous = v # Store forward speed to be used in next step