-
Notifications
You must be signed in to change notification settings - Fork 362
/
scenario_runner.py
executable file
·663 lines (548 loc) · 26.2 KB
/
scenario_runner.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
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
#!/usr/bin/env python
# Copyright (c) 2018-2020 Intel Corporation
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
"""
Welcome to CARLA scenario_runner
This is the main script to be executed when running a scenario.
It loads the scenario configuration, loads the scenario and manager,
and finally triggers the scenario execution.
"""
from __future__ import print_function
import glob
import traceback
import argparse
from argparse import RawTextHelpFormatter
from datetime import datetime
try:
from packaging.version import Version
except ImportError:
from distutils.version import LooseVersion as Version # Python 2 fallback
import importlib
import inspect
import os
import signal
import sys
import time
import json
try:
# requires Python 3.8+
from importlib.metadata import metadata
def get_carla_version():
return Version(metadata("carla")["Version"])
except ModuleNotFoundError:
# backport checking for older Python versions; module is deprecated
import pkg_resources
def get_carla_version():
return Version(pkg_resources.get_distribution("carla").version)
import carla
from srunner.scenarioconfigs.openscenario_configuration import OpenScenarioConfiguration
from srunner.scenariomanager.carla_data_provider import CarlaDataProvider
from srunner.scenariomanager.scenario_manager import ScenarioManager
from srunner.scenarios.open_scenario import OpenScenario
from srunner.scenarios.route_scenario import RouteScenario
from srunner.tools.scenario_parser import ScenarioConfigurationParser
from srunner.tools.route_parser import RouteParser
from srunner.tools.osc2_helper import OSC2Helper
from srunner.scenarios.osc2_scenario import OSC2Scenario
from srunner.scenarioconfigs.osc2_scenario_configuration import OSC2ScenarioConfiguration
# Minimum version of CARLA that is required
MIN_CARLA_VERSION = '0.9.14'
class ScenarioRunner(object):
"""
This is the core scenario runner module. It is responsible for
running (and repeating) a single scenario or a list of scenarios.
Usage:
scenario_runner = ScenarioRunner(args)
scenario_runner.run()
del scenario_runner
"""
ego_vehicles = []
# Tunable parameters
client_timeout = 10.0 # in seconds
wait_for_world = 20.0 # in seconds
# CARLA world and scenario handlers
world = None
manager = None
finished = False
additional_scenario_module = None
agent_instance = None
module_agent = None
def __init__(self, args):
"""
Setup CARLA client and world
Setup ScenarioManager
"""
self._args = args
if args.timeout:
self.client_timeout = float(args.timeout)
# First of all, we need to create the client that will send the requests
# to the simulator. Here we'll assume the simulator is accepting
# requests in the localhost at port 2000.
self.client = carla.Client(args.host, int(args.port))
self.client.set_timeout(self.client_timeout)
carla_version = get_carla_version()
if carla_version < Version(MIN_CARLA_VERSION):
raise ImportError("CARLA version {} or newer required. CARLA version found: {}".format(MIN_CARLA_VERSION, carla_version))
# Load agent if requested via command line args
# If something goes wrong an exception will be thrown by importlib (ok here)
if self._args.agent is not None:
module_name = os.path.basename(args.agent).split('.')[0]
sys.path.insert(0, os.path.dirname(args.agent))
self.module_agent = importlib.import_module(module_name)
# Create the ScenarioManager
self.manager = ScenarioManager(self._args.debug, self._args.sync, self._args.timeout)
# Create signal handler for SIGINT
self._shutdown_requested = False
if sys.platform != 'win32':
signal.signal(signal.SIGHUP, self._signal_handler)
signal.signal(signal.SIGINT, self._signal_handler)
signal.signal(signal.SIGTERM, self._signal_handler)
self._start_wall_time = datetime.now()
def destroy(self):
"""
Cleanup and delete actors, ScenarioManager and CARLA world
"""
self._cleanup()
if self.manager is not None:
del self.manager
if self.world is not None:
del self.world
if self.client is not None:
del self.client
def _signal_handler(self, signum, frame):
"""
Terminate scenario ticking when receiving a signal interrupt
"""
self._shutdown_requested = True
if self.manager:
self.manager.stop_scenario()
self._cleanup()
if not self.manager.get_running_status():
raise RuntimeError("Timeout occurred during scenario execution")
def _get_scenario_class_or_fail(self, scenario):
"""
Get scenario class by scenario name
If scenario is not supported or not found, exit script
"""
# Path of all scenario at "srunner/scenarios" folder + the path of the additional scenario argument
scenarios_list = glob.glob("{}/srunner/scenarios/*.py".format(os.getenv('SCENARIO_RUNNER_ROOT', "./")))
scenarios_list.append(self._args.additionalScenario)
for scenario_file in scenarios_list:
# Get their module
module_name = os.path.basename(scenario_file).split('.')[0]
sys.path.insert(0, os.path.dirname(scenario_file))
scenario_module = importlib.import_module(module_name)
# And their members of type class
for member in inspect.getmembers(scenario_module, inspect.isclass):
if scenario in member:
return member[1]
# Remove unused Python paths
sys.path.pop(0)
print("Scenario '{}' not supported ... Exiting".format(scenario))
sys.exit(-1)
def _cleanup(self):
"""
Remove and destroy all actors
"""
if self.finished:
return
self.finished = True
# Simulation still running and in synchronous mode?
if self.world is not None and self._args.sync:
try:
# Reset to asynchronous mode
settings = self.world.get_settings()
settings.synchronous_mode = False
settings.fixed_delta_seconds = None
self.world.apply_settings(settings)
self.client.get_trafficmanager(int(self._args.trafficManagerPort)).set_synchronous_mode(False)
except RuntimeError:
sys.exit(-1)
self.manager.cleanup()
CarlaDataProvider.cleanup()
for i, _ in enumerate(self.ego_vehicles):
if self.ego_vehicles[i]:
if not self._args.waitForEgo and self.ego_vehicles[i] is not None and self.ego_vehicles[i].is_alive:
print("Destroying ego vehicle {}".format(self.ego_vehicles[i].id))
self.ego_vehicles[i].destroy()
self.ego_vehicles[i] = None
self.ego_vehicles = []
if self.agent_instance:
self.agent_instance.destroy()
self.agent_instance = None
def _prepare_ego_vehicles(self, ego_vehicles):
"""
Spawn or update the ego vehicles
"""
if not self._args.waitForEgo:
for vehicle in ego_vehicles:
self.ego_vehicles.append(CarlaDataProvider.request_new_actor(vehicle.model,
vehicle.transform,
vehicle.rolename,
random_location=vehicle.random_location,
color=vehicle.color,
actor_category=vehicle.category))
else:
ego_vehicle_missing = True
while ego_vehicle_missing:
self.ego_vehicles = []
ego_vehicle_missing = False
for ego_vehicle in ego_vehicles:
ego_vehicle_found = False
carla_vehicles = CarlaDataProvider.get_world().get_actors().filter('vehicle.*')
for carla_vehicle in carla_vehicles:
if carla_vehicle.attributes['role_name'] == ego_vehicle.rolename:
ego_vehicle_found = True
self.ego_vehicles.append(carla_vehicle)
break
if not ego_vehicle_found:
ego_vehicle_missing = True
break
for i, _ in enumerate(self.ego_vehicles):
self.ego_vehicles[i].set_transform(ego_vehicles[i].transform)
self.ego_vehicles[i].set_target_velocity(carla.Vector3D())
self.ego_vehicles[i].set_target_angular_velocity(carla.Vector3D())
self.ego_vehicles[i].apply_control(carla.VehicleControl())
CarlaDataProvider.register_actor(self.ego_vehicles[i], ego_vehicles[i].transform)
# sync state
if CarlaDataProvider.is_sync_mode():
self.world.tick()
else:
self.world.wait_for_tick()
def _analyze_scenario(self, config):
"""
Provide feedback about success/failure of a scenario
"""
# Create the filename
current_time = str(datetime.now().strftime('%Y-%m-%d-%H-%M-%S'))
junit_filename = None
json_filename = None
config_name = config.name
if self._args.outputDir != '':
config_name = os.path.join(self._args.outputDir, config_name)
if self._args.junit:
junit_filename = config_name + current_time + ".xml"
if self._args.json:
json_filename = config_name + current_time + ".json"
filename = None
if self._args.file:
filename = config_name + current_time + ".txt"
if not self.manager.analyze_scenario(self._args.output, filename, junit_filename, json_filename):
print("All scenario tests were passed successfully!")
else:
print("Not all scenario tests were successful")
if not (self._args.output or filename or junit_filename):
print("Please run with --output for further information")
def _record_criteria(self, criteria, name):
"""
Filter the JSON serializable attributes of the criterias and
dumps them into a file. This will be used by the metrics manager,
in case the user wants specific information about the criterias.
"""
file_name = name[:-4] + ".json"
# Filter the attributes that aren't JSON serializable
with open('temp.json', 'w', encoding='utf-8') as fp:
criteria_dict = {}
for criterion in criteria:
criterion_dict = criterion.__dict__
criteria_dict[criterion.name] = {}
for key in criterion_dict:
if key != "name":
try:
key_dict = {key: criterion_dict[key]}
json.dump(key_dict, fp, sort_keys=False, indent=4)
criteria_dict[criterion.name].update(key_dict)
except TypeError:
pass
os.remove('temp.json')
# Save the criteria dictionary into a .json file
with open(file_name, 'w', encoding='utf-8') as fp:
json.dump(criteria_dict, fp, sort_keys=False, indent=4)
def _load_and_wait_for_world(self, town, ego_vehicles=None):
"""
Load a new CARLA world and provide data to CarlaDataProvider
"""
if self._args.reloadWorld:
self.world = self.client.load_world(town)
else:
# if the world should not be reloaded, wait at least until all ego vehicles are ready
ego_vehicle_found = False
if self._args.waitForEgo:
while not ego_vehicle_found and not self._shutdown_requested:
vehicles = self.client.get_world().get_actors().filter('vehicle.*')
for ego_vehicle in ego_vehicles:
ego_vehicle_found = False
for vehicle in vehicles:
if vehicle.attributes['role_name'] == ego_vehicle.rolename:
ego_vehicle_found = True
break
if not ego_vehicle_found:
print("Not all ego vehicles ready. Waiting ... ")
time.sleep(1)
break
self.world = self.client.get_world()
if self._args.sync:
settings = self.world.get_settings()
settings.synchronous_mode = True
settings.fixed_delta_seconds = 1.0 / self._args.frameRate
self.world.apply_settings(settings)
CarlaDataProvider.set_client(self.client)
CarlaDataProvider.set_world(self.world)
# Wait for the world to be ready
if CarlaDataProvider.is_sync_mode():
self.world.tick()
else:
self.world.wait_for_tick()
map_name = CarlaDataProvider.get_map().name.split('/')[-1]
if map_name not in (town, "OpenDriveMap"):
print("The CARLA server uses the wrong map: {}".format(map_name))
print("This scenario requires to use map: {}".format(town))
return False
return True
def _load_and_run_scenario(self, config):
"""
Load and run the scenario given by config
"""
result = False
if not self._load_and_wait_for_world(config.town, config.ego_vehicles):
self._cleanup()
return False
if self._args.agent:
agent_class_name = self.module_agent.__name__.title().replace('_', '')
try:
self.agent_instance = getattr(self.module_agent, agent_class_name)(self._args.agentConfig)
config.agent = self.agent_instance
except Exception as e: # pylint: disable=broad-except
traceback.print_exc()
print("Could not setup required agent due to {}".format(e))
self._cleanup()
return False
CarlaDataProvider.set_traffic_manager_port(int(self._args.trafficManagerPort))
tm = self.client.get_trafficmanager(int(self._args.trafficManagerPort))
tm.set_random_device_seed(int(self._args.trafficManagerSeed))
if self._args.sync:
tm.set_synchronous_mode(True)
# Prepare scenario
print("Preparing scenario: " + config.name)
try:
self._prepare_ego_vehicles(config.ego_vehicles)
if self._args.openscenario:
scenario = OpenScenario(world=self.world,
ego_vehicles=self.ego_vehicles,
config=config,
config_file=self._args.openscenario,
timeout=100000)
elif self._args.route:
scenario = RouteScenario(world=self.world,
config=config,
debug_mode=self._args.debug)
elif self._args.openscenario2:
scenario = OSC2Scenario(world=self.world,
ego_vehicles=self.ego_vehicles,
config=config,
osc2_file=self._args.openscenario2,
timeout=100000)
else:
scenario_class = self._get_scenario_class_or_fail(config.type)
scenario = scenario_class(world=self.world,
ego_vehicles=self.ego_vehicles,
config=config,
randomize=self._args.randomize,
debug_mode=self._args.debug)
except Exception as exception: # pylint: disable=broad-except
print("The scenario cannot be loaded")
traceback.print_exc()
print(exception)
self._cleanup()
return False
try:
if self._args.record:
recorder_name = "{}/{}/{}.log".format(
os.getenv('SCENARIO_RUNNER_ROOT', "./"), self._args.record, config.name)
self.client.start_recorder(recorder_name, True)
# Load scenario and run it
self.manager.load_scenario(scenario, self.agent_instance)
self.manager.run_scenario()
# Provide outputs if required
self._analyze_scenario(config)
# Remove all actors, stop the recorder and save all criterias (if needed)
scenario.remove_all_actors()
if self._args.record:
self.client.stop_recorder()
self._record_criteria(self.manager.scenario.get_criteria(), recorder_name)
result = True
except Exception as e: # pylint: disable=broad-except
traceback.print_exc()
print(e)
result = False
self._cleanup()
return result
def _run_scenarios(self):
"""
Run conventional scenarios (e.g. implemented using the Python API of ScenarioRunner)
"""
result = False
# Load the scenario configurations provided in the config file
scenario_configurations = ScenarioConfigurationParser.parse_scenario_configuration(
self._args.scenario,
self._args.configFile)
if not scenario_configurations:
print("Configuration for scenario {} cannot be found!".format(self._args.scenario))
return result
# Execute each configuration
for config in scenario_configurations:
for _ in range(self._args.repetitions):
self.finished = False
result = self._load_and_run_scenario(config)
self._cleanup()
return result
def _run_route(self):
"""
Run the route scenario
"""
result = False
# retrieve routes
route_configurations = RouteParser.parse_routes_file(self._args.route, self._args.route_id)
for config in route_configurations:
for _ in range(self._args.repetitions):
result = self._load_and_run_scenario(config)
self._cleanup()
return result
def _run_openscenario(self):
"""
Run a scenario based on OpenSCENARIO
"""
# Load the scenario configurations provided in the config file
if not os.path.isfile(self._args.openscenario):
print("File does not exist")
self._cleanup()
return False
openscenario_params = {}
if self._args.openscenarioparams is not None:
for entry in self._args.openscenarioparams.split(','):
[key, val] = [m.strip() for m in entry.split(':')]
openscenario_params[key] = val
config = OpenScenarioConfiguration(self._args.openscenario, self.client, openscenario_params)
result = self._load_and_run_scenario(config)
self._cleanup()
return result
def _run_osc2(self):
"""
Run a scenario based on ASAM OpenSCENARIO 2.0.
https://www.asam.net/static_downloads/public/asam-openscenario/2.0.0/welcome.html
"""
# Load the scenario configurations provided in the config file
if not os.path.isfile(self._args.openscenario2):
print("File does not exist")
self._cleanup()
return False
config = OSC2ScenarioConfiguration(self._args.openscenario2, self.client)
result = self._load_and_run_scenario(config)
self._cleanup()
return result
def run(self):
"""
Run all scenarios according to provided commandline args
"""
result = True
if self._args.openscenario:
result = self._run_openscenario()
elif self._args.route:
result = self._run_route()
elif self._args.openscenario2:
result = self._run_osc2()
else:
result = self._run_scenarios()
print("No more scenarios .... Exiting")
return result
def main():
"""
main function
"""
description = ("CARLA Scenario Runner: Setup, Run and Evaluate scenarios using CARLA\n"
"Current version: " + MIN_CARLA_VERSION)
# pylint: disable=line-too-long
parser = argparse.ArgumentParser(description=description,
formatter_class=RawTextHelpFormatter)
parser.add_argument('-v', '--version', action='version', version='%(prog)s ' + MIN_CARLA_VERSION)
parser.add_argument('--host', default='127.0.0.1',
help='IP of the host server (default: localhost)')
parser.add_argument('--port', default='2000',
help='TCP port to listen to (default: 2000)')
parser.add_argument('--timeout', default="10.0",
help='Set the CARLA client timeout value in seconds')
parser.add_argument('--trafficManagerPort', default='8000',
help='Port to use for the TrafficManager (default: 8000)')
parser.add_argument('--trafficManagerSeed', default='0',
help='Seed used by the TrafficManager (default: 0)')
parser.add_argument('--sync', action='store_true',
help='Forces the simulation to run synchronously')
parser.add_argument('--list', action="store_true", help='List all supported scenarios and exit')
parser.add_argument('--frameRate', default='20', type=float,
help='Frame rate (Hz) to use in \'sync\' mode (default: 20)')
parser.add_argument(
'--scenario', help='Name of the scenario to be executed. Use the preposition \'group:\' to run all scenarios of one class, e.g. ControlLoss or FollowLeadingVehicle')
parser.add_argument('--openscenario', help='Provide an OpenSCENARIO definition')
parser.add_argument('--openscenarioparams', help='Overwrited for OpenSCENARIO ParameterDeclaration')
parser.add_argument('--openscenario2', help='Provide an openscenario2 definition')
parser.add_argument('--route', help='Run a route as a scenario', type=str)
parser.add_argument('--route-id', help='Run a specific route inside that \'route\' file', default='', type=str)
parser.add_argument(
'--agent', help="Agent used to execute the route. Not compatible with non-route-based scenarios.")
parser.add_argument('--agentConfig', type=str, help="Path to Agent's configuration file", default="")
parser.add_argument('--output', action="store_true", help='Provide results on stdout')
parser.add_argument('--file', action="store_true", help='Write results into a txt file')
parser.add_argument('--junit', action="store_true", help='Write results into a junit file')
parser.add_argument('--json', action="store_true", help='Write results into a JSON file')
parser.add_argument('--outputDir', default='', help='Directory for output files (default: this directory)')
parser.add_argument('--configFile', default='', help='Provide an additional scenario configuration file (*.xml)')
parser.add_argument('--additionalScenario', default='', help='Provide additional scenario implementations (*.py)')
parser.add_argument('--debug', action="store_true", help='Run with debug output')
parser.add_argument('--reloadWorld', action="store_true",
help='Reload the CARLA world before starting a scenario (default=True)')
parser.add_argument('--record', type=str, default='',
help='Path were the files will be saved, relative to SCENARIO_RUNNER_ROOT.\nActivates the CARLA recording feature and saves to file all the criteria information.')
parser.add_argument('--randomize', action="store_true", help='Scenario parameters are randomized')
parser.add_argument('--repetitions', default=1, type=int, help='Number of scenario executions')
parser.add_argument('--waitForEgo', action="store_true", help='Connect the scenario to an existing ego vehicle')
arguments = parser.parse_args()
# pylint: enable=line-too-long
OSC2Helper.wait_for_ego = arguments.waitForEgo
if arguments.list:
print("Currently the following scenarios are supported:")
print(*ScenarioConfigurationParser.get_list_of_scenarios(arguments.configFile), sep='\n')
return 1
if not arguments.scenario and not arguments.openscenario and not arguments.route and not arguments.openscenario2:
print("Please specify either a scenario or use the route mode\n\n")
parser.print_help(sys.stdout)
return 1
if arguments.route and (arguments.openscenario or arguments.scenario):
print("The route mode cannot be used together with a scenario (incl. OpenSCENARIO)'\n\n")
parser.print_help(sys.stdout)
return 1
if arguments.agent and (arguments.openscenario or arguments.scenario):
print("Agents are currently only compatible with route scenarios'\n\n")
parser.print_help(sys.stdout)
return 1
if arguments.openscenarioparams and not arguments.openscenario:
print("WARN: Ignoring --openscenarioparams when --openscenario is not specified")
if arguments.route:
arguments.reloadWorld = True
if arguments.agent:
arguments.sync = True
scenario_runner = None
result = True
try:
scenario_runner = ScenarioRunner(arguments)
result = scenario_runner.run()
except Exception: # pylint: disable=broad-except
traceback.print_exc()
finally:
if scenario_runner is not None:
scenario_runner.destroy()
del scenario_runner
return not result
if __name__ == "__main__":
sys.exit(main())