-
Notifications
You must be signed in to change notification settings - Fork 1
/
mainCARLA.py
592 lines (496 loc) · 28.3 KB
/
mainCARLA.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
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
#!/usr/bin/env python
import glob
import os
import sys
import carla
from carla import *
import random
import pygame
import queue
from commonroad.common.file_reader import CommonRoadFileReader
from commonroad.visualization.mp_renderer import MPRenderer
from commonroad.visualization.draw_params import MPDrawParams
from commonroad.geometry.shape import Rectangle
from commonroad.visualization.draw_params import ShapeParams
from shapely.geometry import Point
import matplotlib.pyplot as plt
import matplotlib.image as mpimg
from matplotlib.backends.backend_agg import FigureCanvasAgg
from matplotlib.figure import Figure
import numpy as np
import os
import pickle
import cv2
import time
from copy import deepcopy
from vehicle.vehicleParameter import vehicleParameter
from maneuverAutomaton.ManeuverAutomaton import ManeuverAutomaton
from src.highLevelPlanner import highLevelPlanner
from src.lowLevelPlannerManeuverAutomaton import lowLevelPlannerManeuverAutomaton
from src.lowLevelPlannerOptimization import lowLevelPlannerOptimization
from auxiliary.prediction import prediction
from auxiliary.overlappingLanelets import overlappingLanelets
from commonroad.scenario.lanelet import Lanelet
from commonroad.scenario.lanelet import LaneletNetwork
from commonroad.planning.goal import GoalRegion
from commonroad.scenario.state import CustomState
from commonroad.scenario.state import InitialState
from commonroad.common.util import Interval
from commonroad.scenario.traffic_sign import TrafficLight, TrafficLightCycleElement, TrafficLightState
from commonroad.planning.planning_problem import PlanningProblem
from commonroad.planning.planning_problem import PlanningProblemSet
from commonroad_route_planner.route_planner import RoutePlanner
from commonroad_route_planner.utility.visualization import visualize_route
from commonroad.visualization.util import collect_center_line_colors
from commonroad.geometry.shape import Rectangle
from commonroad.scenario.obstacle import DynamicObstacle, ObstacleType
import warnings
warnings.filterwarnings("ignore")
MAP = 'Town01' # CARLA map
PLANNER = 'Optimization' # motion planner ('Automaton' or 'Optimization')
HORIZON = 3 # planning horizon (in seconds)
REPLAN = 0.3 # time after which the trajectory is re-planned (in seconds)
FREQUENCY = 25 # control frequency (in Hertz)
SENSORRANGE = 100 # sensor range of the car (in meters)
CARS = 100 # number of cars in the map
REAL_DYNAMICS = True # use real car dynamics from the CARLA vehicle model
VISUALIZE = True # visualize the planned trajectory
VIDEO = True # create a video
class CarlaSyncMode(object):
"""
Context manager to synchronize output from different sensors. Synchronous
mode is enabled as long as we are inside this context
with CarlaSyncMode(world, sensors) as sync_mode:
while True:
data = sync_mode.tick(timeout=1.0)
"""
def __init__(self, world, *sensors, **kwargs):
self.world = world
self.sensors = sensors
self.frame = None
self.delta_seconds = 1.0 / kwargs.get('fps', FREQUENCY)
self._queues = []
self._settings = None
def __enter__(self):
self._settings = self.world.get_settings()
self.frame = self.world.apply_settings(carla.WorldSettings(
no_rendering_mode=False,
synchronous_mode=True,
fixed_delta_seconds=self.delta_seconds))
def make_queue(register_event):
q = queue.Queue()
register_event(q.put)
self._queues.append(q)
make_queue(self.world.on_tick)
for sensor in self.sensors:
make_queue(sensor.listen)
return self
def tick(self, timeout):
self.frame = self.world.tick()
data = [self._retrieve_data(q, timeout) for q in self._queues]
assert all(x.frame == self.frame for x in data)
return data
def __exit__(self, *args, **kwargs):
self.world.apply_settings(self._settings)
def _retrieve_data(self, sensor_queue, timeout):
while True:
data = sensor_queue.get(timeout=timeout)
if data.frame == self.frame:
return data
def draw_image(surface, image, blend=False):
array = np.frombuffer(image.raw_data, dtype=np.dtype("uint8"))
array = np.reshape(array, (image.height, image.width, 4))
array = array[:, :, :3]
array = array[:, :, ::-1]
image_surface = pygame.surfarray.make_surface(array.swapaxes(0, 1))
if blend:
image_surface.set_alpha(100)
surface.blit(image_surface, (0, 0))
def should_quit():
for event in pygame.event.get():
if event.type == pygame.QUIT:
return True
elif event.type == pygame.KEYUP:
if event.key == pygame.K_ESCAPE:
return True
return False
def main():
# initialize CARLA
actor_list = []
pygame.init()
display = pygame.display.set_mode((800, 600), pygame.HWSURFACE | pygame.DOUBLEBUF)
client = carla.Client('localhost', 2000)
client.set_timeout(5.0)
world = client.get_world()
traffic_manager = client.get_trafficmanager(3000)
client.load_world(MAP)
# load parameter for the car
param = vehicleParameter()
param['a_max'] = 6
param['wheelbase'] = 2.7
# load maneuver automaton
filehandler = open('./maneuverAutomaton/maneuverAutomaton.obj', 'rb')
MA = pickle.load(filehandler)
# load the CommonRoad scenario
scenario, planning_problem = CommonRoadFileReader(os.path.join('auxiliary', MAP + '.xml')).open()
# determine overlapping laneletstrajectories
overlaps = overlappingLanelets(scenario)
# create random planning problem
spawn_points = world.get_map().get_spawn_points()
start = random.choice(spawn_points)
initial_state = InitialState(position=np.array([start.location.x, -start.location.y]),
velocity=0, orientation=-np.deg2rad(start.rotation.yaw), yaw_rate=0,
slip_angle=0, time_step=0)
goal = random.choice(spawn_points)
id = scenario.lanelet_network.find_lanelet_by_position([np.array([goal.location.x, -goal.location.y])])
l = scenario.lanelet_network.find_lanelet_by_id(id[0][0])
goal_state = CustomState(position=l.polygon, time_step=Interval(0, 0))
goal_region = GoalRegion([goal_state], lanelets_of_goal_position=None)
planning_problem = PlanningProblemSet([PlanningProblem(1, initial_state, goal_region)])
# plan route
planning_problem = list(planning_problem.planning_problem_dict.values())[0]
route_planner = RoutePlanner(scenario, planning_problem, backend=RoutePlanner.Backend.NETWORKX_REVERSED)
candidate_holder = route_planner.plan_routes()
route = candidate_holder.retrieve_first_route()
# initialization
state = planning_problem.initial_state
x0 = np.concatenate((state.position, np.array([state.velocity, state.orientation])))
start_pose = Transform(Location(x=x0[0], y=-x0[1], z=0.1), Rotation(pitch=0.0, yaw=-np.rad2deg(x0[3]), roll=0.0))
lanelet = route.list_ids_lanelets[0]
cnt_init = 0
traj = {'x': [x0], 'u': [], 't': [0]}
comp_time = {'high': [], 'all': []}
t = REPLAN
plt.figure(figsize=(7, 7))
horizon = int(np.round(HORIZON/scenario.dt))
if not os.path.isdir('results'):
os.mkdir('results')
if not os.path.isdir(os.path.join('results', 'CARLA')):
os.mkdir(os.path.join('results', 'CARLA'))
if VIDEO:
fourcc = cv2.VideoWriter_fourcc('m', 'p', '4', 'v')
video = cv2.VideoWriter(os.path.join('results', 'CARLA', 'videoCARLA.mp4'), fourcc, FREQUENCY, (800+600, 600))
# set weather
w = [carla.WeatherParameters.ClearNoon, carla.WeatherParameters.CloudyNoon, carla.WeatherParameters.WetNoon,
carla.WeatherParameters.WetCloudyNoon, carla.WeatherParameters.SoftRainNoon,
carla.WeatherParameters.MidRainyNoon, carla.WeatherParameters.HardRainNoon,
carla.WeatherParameters.ClearSunset, carla.WeatherParameters.CloudySunset, carla.WeatherParameters.WetSunset,
carla.WeatherParameters.WetCloudySunset, carla.WeatherParameters.SoftRainSunset,
carla.WeatherParameters.MidRainSunset, carla.WeatherParameters.HardRainSunset]
index = np.random.randint(0, len(w)-1)
world.set_weather(w[index])
# create traffic
vehicle_blueprints = world.get_blueprint_library().filter('*vehicle*')
spawn_points = world.get_map().get_spawn_points()
for i in range(0, CARS):
point = random.choice(spawn_points)
if (point.location.x - x0[0])**2 + (-point.location.y - x0[1])**2 > 10**2:
world.try_spawn_actor(random.choice(vehicle_blueprints), point)
for v in world.get_actors().filter('*vehicle*'):
v.set_autopilot(True, traffic_manager.get_port())
try:
# select vehicle model
blueprint_library = world.get_blueprint_library()
vehicle = world.spawn_actor(blueprint_library.find('vehicle.tesla.model3'), start_pose)
actor_list.append(vehicle)
vehicle.set_simulate_physics(REAL_DYNAMICS)
param['length'] = 2*vehicle.bounding_box.extent.x
param['width'] = 2*vehicle.bounding_box.extent.y
# select camara view
camera_rgb = world.spawn_actor(blueprint_library.find('sensor.camera.rgb'),
carla.Transform(carla.Location(x=-5.5, z=2.8),
carla.Rotation(pitch=-15)), attach_to=vehicle)
actor_list.append(camera_rgb)
# main control loop
with CarlaSyncMode(world, camera_rgb, fps=FREQUENCY) as sync_mode:
while True:
if should_quit():
return
# advance the simulation and wait for the data.
snapshot, image_rgb = sync_mode.tick(timeout=2.0)
# plan a new trajectory
if t < REPLAN:
t = t + 1/FREQUENCY
else:
t = 0
# get current position of the ego vehicle
transform = vehicle.get_transform()
velocity = vehicle.get_velocity()
velocity = np.sqrt(velocity.x ** 2 + velocity.y ** 2 + velocity.z ** 2)
x0 = np.array([transform.location.x, -transform.location.y, velocity, -np.deg2rad(transform.rotation.yaw)])
# check if goal has been reached
if (goal.location.x - x0[0])**2 + (goal.location.y + x0[1])**2 < 10**2:
print('####################################################')
print(' GOAL REACHED')
print('####################################################')
return
# predict the future positions of the other vehicles
scenario_ = deepcopy(scenario)
vehicles = []
for v in world.get_actors().filter('*vehicle*'):
transform = v.get_transform()
if (transform.location.x - x0[0])**2 + (-transform.location.y - x0[1])**2 < SENSORRANGE**2 and \
(transform.location.x - x0[0]) ** 2 + (-transform.location.y - x0[1]) ** 2 > 0.1:
orientation = np.deg2rad(transform.rotation.yaw)
vel = v.get_velocity()
velocity = np.sqrt(vel.x ** 2 + vel.y ** 2 + vel.z ** 2)
velocity = max(0, velocity - 1)
acc = v.get_acceleration()
acceleration = np.sqrt(acc.x ** 2 + acc.y ** 2 + acc.z ** 2) * np.sign(acc.x*vel.x + acc.y*vel.y)
length = 2*v.bounding_box.extent.x
width = 2*v.bounding_box.extent.y
if length == 0:
length = 2
if width == 0:
width = 1
state = CustomState(position=np.array([transform.location.x, -transform.location.y]),
velocity=velocity, orientation=-orientation, time_step=0)
shape = Rectangle(width=width, length=length)
dynamic_obstacle = DynamicObstacle(scenario.generate_object_id(), ObstacleType.CAR, shape,
state)
scenario_.add_objects(dynamic_obstacle)
vehicles.append(Rectangle(center=state.position, orientation=state.orientation,
width=width, length=length))
scenario_ = prediction(scenario_, horizon, x0, overlapping_lanelets=overlaps)
# consider red traffic lights
points_all = []
for traffic_light in world.get_actors().filter('*traffic_light*'):
loc = traffic_light.get_location()
if str(traffic_light.get_state()) == 'Red' or str(traffic_light.get_state()) == 'Yellow' \
and (loc.x - x0[0])**2 + (-loc.y - x0[1])**2 < SENSORRANGE**2:
points = []
for wp in traffic_light.get_affected_lane_waypoints():
points.append(np.array([wp.transform.location.x, -wp.transform.location.y]))
points_all = points_all + points
lanesPrev = scenario.lanelet_network.find_lanelet_by_position([points[-1]])
lanesPrev_ = []
for lane in list(np.unique(np.asarray(lanesPrev))):
l = scenario.lanelet_network.find_lanelet_by_id(lane)
d1 = (l.center_vertices[-1, 0] - points[-1][0])**2 + \
(l.center_vertices[-1, 1] - points[-1][1])**2
d2 = (l.center_vertices[-2, 0] - points[-1][0]) ** 2 + \
(l.center_vertices[-2, 1] - points[-1][1]) ** 2
if d1 < d2:
lanesPrev_ = lanesPrev_ + l.successor
else:
lanesPrev_.append(lane)
lanes = []
for lane in list(np.unique(np.asarray(lanesPrev_))):
try:
l = scenario.lanelet_network.find_lanelet_by_id(lane)
lanes = lanes + l.predecessor
except:
test = 1
lanes = list(np.unique(np.asarray(lanes)))
for lane in lanes:
try:
l = scenario.lanelet_network.find_lanelet_by_id(lane)
if not l.adj_left is None and l.adj_left_same_direction:
lanes = lanes + [l.adj_left]
if not l.adj_right is None and l.adj_right_same_direction:
lanes = lanes + [l.adj_right]
except:
test = 1
lanes = list(np.unique(np.asarray(lanes)))
if len(lanes) > 0:
cycle = TrafficLightCycleElement(TrafficLightState('red'), horizon * scenario.dt)
traffic_light = TrafficLight(scenario_.generate_object_id(), [cycle])
_ = scenario_.lanelet_network.add_traffic_light(traffic_light, lanes)
# get lanelet for the current state
lane = scenario.lanelet_network.find_lanelet_by_id(lanelet)
if not lane.polygon.shapely_object.contains(Point(x0[0], x0[1])):
for i in range(cnt_init, len(route.list_ids_lanelets)):
l = scenario.lanelet_network.find_lanelet_by_id(route.list_ids_lanelets[i])
if l.polygon.shapely_object.contains(Point(x0[0], x0[1])):
cnt_init = i
lanelet = l.lanelet_id
# create motion planning problem
goal_states = []
lanelets_of_goal_position = {}
dist_max = x0[2] * scenario.dt * horizon + 0.5 * param['a_max'] * (scenario.dt * horizon) ** 2
dist = 0
for i in range(cnt_init, len(route.list_ids_lanelets)):
goal_id = route.list_ids_lanelets[i]
goal_lane = scenario.lanelet_network.find_lanelet_by_id(goal_id)
goal_states.append(
CustomState(time_step=Interval(horizon, horizon), position=goal_lane.polygon))
lanelets_of_goal_position[len(goal_states) - 1] = [goal_id]
if i > cnt_init:
dist = dist + goal_lane.distance[-1]
if dist > dist_max:
break
goal_region = GoalRegion(goal_states, lanelets_of_goal_position=lanelets_of_goal_position)
initial_state = InitialState(position=x0[0:2], velocity=x0[2], orientation=x0[3], yaw_rate=0,
slip_angle=0, time_step=0)
planning_problem = PlanningProblemSet([PlanningProblem(1, initial_state, goal_region)])
# store planning problem
data = {'scenario': scenario_, 'problem': planning_problem}
filehandler = open(os.path.join('results', 'CARLA', 'CARLAdata.obj'), 'wb')
pickle.dump(data, filehandler)
# solve motion planning problem
start_time = time.time()
try:
if PLANNER == 'Automaton':
plan, space, ref_traj = highLevelPlanner(scenario_, planning_problem, param,
compute_free_space=True, minimum_safe_distance=0.5,
improve_velocity_profile=True)
else:
plan, space, ref_traj = highLevelPlanner(scenario_, planning_problem, param,
compute_free_space=False,
minimum_safe_distance=0.5,
improve_velocity_profile=True)
except Exception as e:
print(e)
return
comp_time['high'].append(time.time() - start_time)
if PLANNER == 'Automaton':
x, u, controller = lowLevelPlannerManeuverAutomaton(scenario_, planning_problem, param, space,
ref_traj, MA)
elif PLANNER == 'Optimization':
x, u, controller = lowLevelPlannerOptimization(scenario_, planning_problem, param,
space, ref_traj, feedback_control=True,
R_diff=np.diag([0, 0.1]))
else:
raise Exception('Motion planner not supported! The available planners are "Automaton" and "Optimization".')
comp_time['all'].append(time.time() - start_time)
# update car position and orientation
if REAL_DYNAMICS:
transform = vehicle.get_transform()
velocity = vehicle.get_velocity()
velocity = np.sqrt(velocity.x ** 2 + velocity.y ** 2 + velocity.z ** 2)
x_meas = np.expand_dims(np.array([transform.location.x, -transform.location.y,
velocity, -np.deg2rad(transform.rotation.yaw)]), axis=1)
traj['x'].append(x_meas[:, 0])
x_meas[0, 0] = x_meas[0, 0] - np.cos(x_meas[3, 0]) * param['b']
x_meas[1, 0] = x_meas[1, 0] - np.sin(x_meas[3, 0]) * param['b']
u = controller.get_control_input(t, x_meas)
acc = u[0] / 6.17
steer = -u[1]
if abs(velocity) < 0.5:
steer = 0
if all(ref_traj[2, :] < 0.5) and acc > 0:
acc = 0
if acc > 0:
vehicle.apply_control(carla.VehicleControl(throttle=acc, brake=0, steer=steer, manual_gear_shift=True, gear=2))
else:
vehicle.apply_control(carla.VehicleControl(throttle=0, brake=-acc, steer=steer, manual_gear_shift=True, gear=2))
traj['u'].append(np.array([acc, steer]))
traj['t'].append(traj['t'][-1] + 1 / FREQUENCY)
else:
x0 = x[:, int(np.floor(t/param['time_step']))]
pose = Transform(Location(x=x0[0], y=-x0[1], z=0.3),
Rotation(pitch=0.0, yaw=-np.rad2deg(x0[3]), roll=0.0))
vehicle.set_transform(pose)
# draw the display.
draw_image(display, image_rgb)
pygame.display.flip()
# visualize the planned trajectory
if VISUALIZE:
plt.cla()
rnd = MPRenderer()
canvas = FigureCanvasAgg(rnd.f)
cnt_time = int(np.floor(t/param['time_step']))
rnd.draw_params.time_begin = cnt_time
rnd.draw_params.time_end = horizon
rnd.draw_params.planning_problem_set.planning_problem.initial_state.state.draw_arrow = False
rnd.draw_params.planning_problem_set.planning_problem.initial_state.state.radius = 0
scenario.draw(rnd)
planning_problem.draw(rnd)
# plot traffic lights
if len(scenario_.lanelet_network.traffic_lights) > 0:
status = collect_center_line_colors(scenario_.lanelet_network,
scenario_.lanelet_network.traffic_lights, 0)
settings = ShapeParams(opacity=1, edgecolor="k", linewidth=0.0, facecolor='r')
for l in status.keys():
lane = scenario_.lanelet_network.find_lanelet_by_id(l)
for j in range(len(lane.distance) - 1):
center = 0.5 * (lane.center_vertices[j, :] + lane.center_vertices[j + 1, :])
d = lane.center_vertices[j + 1, :] - lane.center_vertices[j, :]
r = Rectangle(length=np.linalg.norm(d), width=0.6, center=center,
orientation=np.arctan2(d[1], d[0]))
r.draw(rnd, settings)
# plot prediction for the other vehicles
for d in scenario_.dynamic_obstacles:
for j in range(len(d.prediction.trajectory.state_list), 0, -1):
s = d.prediction.trajectory.state_list[j - 1]
if s.time_step >= cnt_time:
if s.time_step == cnt_time:
settings = ShapeParams(opacity=1, edgecolor="k", linewidth=1.0,
facecolor='#1d7eea')
else:
settings = ShapeParams(opacity=0.2, edgecolor="k", linewidth=0.0,
facecolor='#1d7eea')
r = Rectangle(length=d.obstacle_shape.length, width=d.obstacle_shape.width,
center=s.position,
orientation=s.orientation)
r.draw(rnd, settings)
if d.prediction.trajectory.state_list[-1].time_step < cnt_time:
s = d.prediction.trajectory.state_list[-1]
settings = ShapeParams(opacity=1, edgecolor="k", linewidth=1.0, facecolor='#1d7eea')
r = Rectangle(length=d.obstacle_shape.length, width=d.obstacle_shape.width,
center=s.position, orientation=s.orientation)
r.draw(rnd, settings)
for v in vehicles:
found = False
for d in scenario_.dynamic_obstacles:
if np.linalg.norm(d.initial_state.position - v.center) < 0.1:
found = True
break
if not found:
settings = ShapeParams(opacity=1, edgecolor="k", linewidth=1.0, facecolor='#1d7eea')
v.draw(rnd, settings)
# plot planned trajectory
for j in range(x.shape[1] - 1, -1, -1):
if j >= cnt_time:
if j == cnt_time:
settings = ShapeParams(opacity=1, edgecolor="k", linewidth=1.0, facecolor='#d95558')
else:
settings = ShapeParams(opacity=0.2, edgecolor="k", linewidth=0.0, facecolor='#d95558')
r = Rectangle(length=param['length'], width=param['width'],
center=np.array([x[0, j], x[1, j]]),
orientation=x[3, j])
r.draw(rnd, settings)
rnd.render()
plt.xlim([x[0, cnt_time] - 40, x[0, cnt_time] + 40])
plt.ylim([x[1, cnt_time] - 40, x[1, cnt_time] + 40])
ax = plt.gca()
ax.axes.xaxis.set_ticks([])
ax.axes.yaxis.set_ticks([])
plt.pause(0.01)
# create video
if VIDEO:
# get image from CARLA
array = np.frombuffer(image_rgb.raw_data, dtype=np.dtype("uint8"))
frame1 = np.reshape(array, (image_rgb.height, image_rgb.width, 4))
frame1 = frame1[:, :, :3]
# extract image of planned trajectory from plotted figure
canvas.draw()
buf = canvas.buffer_rgba()
frame2 = np.asarray(buf)
frame2 = frame2[53:653, 57:657, :]
frame2 = cv2.cvtColor(frame2, cv2.COLOR_RGB2BGR)
# combine images
frame = np.concatenate((frame1, frame2), axis=1)
# add frame to video
video.write(frame)
finally:
# write video to file
if VIDEO:
cv2.destroyAllWindows()
video.release()
# write computation times to file
filehandler = open(os.path.join('results', 'CARLA', 'computationTime.obj'), 'wb')
pickle.dump(comp_time, filehandler)
# write trajectory to file
filehandler = open(os.path.join('results', 'CARLA', 'trajectory.obj'), 'wb')
pickle.dump(traj, filehandler)
print('destroying actors.')
for actor in actor_list:
actor.destroy()
pygame.quit()
print('done.')
if __name__ == '__main__':
try:
main()
except KeyboardInterrupt:
print('\nCancelled by user. Bye!')