-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathleaderboard_evaluator.py
465 lines (367 loc) · 17.6 KB
/
leaderboard_evaluator.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
#!/usr/bin/env python
# Copyright (c) 2018-2019 Intel Corporation.
# authors: German Ros ([email protected]), Felipe Codevilla ([email protected])
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
"""
CARLA Challenge Evaluator Routes
Provisional code to evaluate Autonomous Agents for the CARLA Autonomous Driving challenge
"""
from __future__ import print_function
import traceback
import argparse
from argparse import RawTextHelpFormatter
from datetime import datetime
from distutils.version import LooseVersion
import importlib
import os
import pkg_resources
import sys
import carla
import signal
from srunner.scenariomanager.carla_data_provider import *
from srunner.scenariomanager.timer import GameTime
from srunner.scenariomanager.watchdog import Watchdog
from leaderboard.scenarios.scenario_manager import ScenarioManager
from leaderboard.scenarios.route_scenario import RouteScenario
from leaderboard.envs.sensor_interface import SensorConfigurationInvalid
from leaderboard.autoagents.agent_wrapper import AgentWrapper, AgentError
from leaderboard.utils.statistics_manager import StatisticsManager
from leaderboard.utils.route_indexer import RouteIndexer
sensors_to_icons = {
'sensor.camera.rgb': 'carla_camera',
'sensor.lidar.ray_cast': 'carla_lidar',
'sensor.other.radar': 'carla_radar',
'sensor.other.gnss': 'carla_gnss',
'sensor.other.imu': 'carla_imu',
'sensor.opendrive_map': 'carla_opendrive_map',
'sensor.speedometer': 'carla_speedometer'
}
class LeaderboardEvaluator(object):
"""
TODO: document me!
"""
ego_vehicles = []
# Tunable parameters
client_timeout = 10.0 # in seconds
wait_for_world = 20.0 # in seconds
frame_rate = 20.0 # in Hz
def __init__(self, args, statistics_manager):
"""
Setup CARLA client and world
Setup ScenarioManager
"""
self.statistics_manager = statistics_manager
self.sensors = None
self.sensor_icons = []
self._vehicle_lights = carla.VehicleLightState.Position | carla.VehicleLightState.LowBeam
# 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))
if args.timeout:
self.client_timeout = float(args.timeout)
self.client.set_timeout(self.client_timeout)
self.traffic_manager = self.client.get_trafficmanager(int(args.trafficManagerPort))
dist = pkg_resources.get_distribution("carla")
if dist.version != 'leaderboard':
if LooseVersion(dist.version) < LooseVersion('0.9.10'):
raise ImportError("CARLA version 0.9.10.1 or newer required. CARLA version found: {}".format(dist))
# Load agent
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(args.timeout, args.debug > 1)
# Time control for summary purposes
self._start_time = GameTime.get_time()
self._end_time = None
# Create the agent timer
self._agent_watchdog = Watchdog(int(float(args.timeout)))
signal.signal(signal.SIGINT, self._signal_handler)
def _signal_handler(self, signum, frame):
"""
Terminate scenario ticking when receiving a signal interrupt
"""
if self._agent_watchdog and not self._agent_watchdog.get_status():
raise RuntimeError("Timeout: Agent took too long to setup")
elif self.manager:
self.manager.signal_handler(signum, frame)
def __del__(self):
"""
Cleanup and delete actors, ScenarioManager and CARLA world
"""
self._cleanup()
if hasattr(self, 'manager') and self.manager:
del self.manager
if hasattr(self, 'world') and self.world:
del self.world
def _cleanup(self):
"""
Remove and destroy all actors
"""
# Simulation still running and in synchronous mode?
if self.manager and self.manager.get_running_status() \
and hasattr(self, 'world') and self.world:
# Reset to asynchronous mode
settings = self.world.get_settings()
settings.synchronous_mode = False
settings.fixed_delta_seconds = None
self.world.apply_settings(settings)
self.traffic_manager.set_synchronous_mode(False)
if self.manager:
self.manager.cleanup()
CarlaDataProvider.cleanup()
for i, _ in enumerate(self.ego_vehicles):
if self.ego_vehicles[i]:
self.ego_vehicles[i].destroy()
self.ego_vehicles[i] = None
self.ego_vehicles = []
if self._agent_watchdog:
self._agent_watchdog.stop()
if hasattr(self, 'agent_instance') and self.agent_instance:
self.agent_instance.destroy()
self.agent_instance = None
if hasattr(self, 'statistics_manager') and self.statistics_manager:
self.statistics_manager.scenario = None
def _prepare_ego_vehicles(self, ego_vehicles, wait_for_ego_vehicles=False):
"""
Spawn or update the ego vehicles
"""
if not wait_for_ego_vehicles:
for vehicle in ego_vehicles:
self.ego_vehicles.append(CarlaDataProvider.request_new_actor(vehicle.model,
vehicle.transform,
vehicle.rolename,
color=vehicle.color,
vehicle_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)
# sync state
CarlaDataProvider.get_world().tick()
def _load_and_wait_for_world(self, args, town, ego_vehicles=None):
"""
Load a new CARLA world and provide data to CarlaDataProvider
"""
self.world = self.client.load_world(town)
settings = self.world.get_settings()
settings.fixed_delta_seconds = 1.0 / self.frame_rate
settings.synchronous_mode = True
self.world.apply_settings(settings)
self.world.reset_all_traffic_lights()
CarlaDataProvider.set_client(self.client)
CarlaDataProvider.set_world(self.world)
CarlaDataProvider.set_traffic_manager_port(int(args.trafficManagerPort))
self.traffic_manager.set_synchronous_mode(True)
self.traffic_manager.set_random_device_seed(int(args.trafficManagerSeed))
# Wait for the world to be ready
if CarlaDataProvider.is_sync_mode():
self.world.tick()
else:
self.world.wait_for_tick()
if CarlaDataProvider.get_map().name != town:
raise Exception("The CARLA server uses the wrong map!"
"This scenario requires to use map {}".format(town))
def _register_statistics(self, config, checkpoint, entry_status, crash_message=""):
"""
Computes and saved the simulation statistics
"""
# register statistics
current_stats_record = self.statistics_manager.compute_route_statistics(
config,
self.manager.scenario_duration_system,
self.manager.scenario_duration_game,
crash_message
)
print("\033[1m> Registering the route statistics\033[0m")
self.statistics_manager.save_record(current_stats_record, config.index, checkpoint)
self.statistics_manager.save_entry_status(entry_status, False, checkpoint)
def _load_and_run_scenario(self, args, config):
"""
Load and run the scenario given by config.
Depending on what code fails, the simulation will either stop the route and
continue from the next one, or report a crash and stop.
"""
crash_message = ""
entry_status = "Started"
print("\n\033[1m========= Preparing {} (repetition {}) =========".format(config.name, config.repetition_index))
print("> Setting up the agent\033[0m")
# Prepare the statistics of the route
self.statistics_manager.set_route(config.name, config.index)
# Set up the user's agent, and the timer to avoid freezing the simulation
try:
self._agent_watchdog.start()
agent_class_name = getattr(self.module_agent, 'get_entry_point')()
self.agent_instance = getattr(self.module_agent, agent_class_name)(args.agent_config)
config.agent = self.agent_instance
# Check and store the sensors
if not self.sensors:
self.sensors = self.agent_instance.sensors()
track = self.agent_instance.track
AgentWrapper.validate_sensor_configuration(self.sensors, track, args.track)
self.sensor_icons = [sensors_to_icons[sensor['type']] for sensor in self.sensors]
self.statistics_manager.save_sensors(self.sensor_icons, args.checkpoint)
self._agent_watchdog.stop()
except SensorConfigurationInvalid as e:
# The sensors are invalid -> set the ejecution to rejected and stop
print("\n\033[91mThe sensor's configuration used is invalid:")
print("> {}\033[0m\n".format(e))
traceback.print_exc()
crash_message = "Agent's sensors were invalid"
entry_status = "Rejected"
self._register_statistics(config, args.checkpoint, entry_status, crash_message)
self._cleanup()
sys.exit(-1)
except Exception as e:
# The agent setup has failed -> start the next route
print("\n\033[91mCould not set up the required agent:")
print("> {}\033[0m\n".format(e))
traceback.print_exc()
crash_message = "Agent couldn't be set up"
self._register_statistics(config, args.checkpoint, entry_status, crash_message)
self._cleanup()
return
print("\033[1m> Loading the world\033[0m")
# Load the world and the scenario
try:
self._load_and_wait_for_world(args, config.town, config.ego_vehicles)
self._prepare_ego_vehicles(config.ego_vehicles, False)
scenario = RouteScenario(world=self.world, config=config, debug_mode=args.debug)
self.statistics_manager.set_scenario(scenario.scenario)
# Night mode
if config.weather.sun_altitude_angle < 0.0:
for vehicle in scenario.ego_vehicles:
vehicle.set_light_state(carla.VehicleLightState(self._vehicle_lights))
# Load scenario and run it
if args.record:
self.client.start_recorder("{}/{}_rep{}.log".format(args.record, config.name, config.repetition_index))
self.manager.load_scenario(scenario, self.agent_instance, config.repetition_index)
except Exception as e:
# The scenario is wrong -> set the ejecution to crashed and stop
print("\n\033[91mThe scenario could not be loaded:")
print("> {}\033[0m\n".format(e))
traceback.print_exc()
crash_message = "Simulation crashed"
entry_status = "Crashed"
self._register_statistics(config, args.checkpoint, entry_status, crash_message)
if args.record:
self.client.stop_recorder()
self._cleanup()
sys.exit(-1)
print("\033[1m> Running the route\033[0m")
# Run the scenario
try:
self.manager.run_scenario()
except AgentError as e:
# The agent has failed -> stop the route
print("\n\033[91mStopping the route, the agent has crashed:")
print("> {}\033[0m\n".format(e))
traceback.print_exc()
crash_message = "Agent crashed"
except Exception as e:
print("\n\033[91mError during the simulation:")
print("> {}\033[0m\n".format(e))
traceback.print_exc()
crash_message = "Simulation crashed"
entry_status = "Crashed"
# Stop the scenario
try:
print("\033[1m> Stopping the route\033[0m")
self.manager.stop_scenario()
self._register_statistics(config, args.checkpoint, entry_status, crash_message)
if args.record:
self.client.stop_recorder()
# Remove all actors
scenario.remove_all_actors()
self._cleanup()
except Exception as e:
print("\n\033[91mFailed to stop the scenario, the statistics might be empty:")
print("> {}\033[0m\n".format(e))
traceback.print_exc()
crash_message = "Simulation crashed"
if crash_message == "Simulation crashed":
sys.exit(-1)
def run(self, args):
"""
Run the challenge mode
"""
route_indexer = RouteIndexer(args.routes, args.scenarios, args.repetitions)
if args.resume:
route_indexer.resume(args.checkpoint)
self.statistics_manager.resume(args.checkpoint)
else:
self.statistics_manager.clear_record(args.checkpoint)
route_indexer.save_state(args.checkpoint)
while route_indexer.peek():
# setup
config = route_indexer.next()
# run
self._load_and_run_scenario(args, config)
route_indexer.save_state(args.checkpoint)
# save global statistics
print("\033[1m> Registering the global statistics\033[0m")
global_stats_record = self.statistics_manager.compute_global_statistics(route_indexer.total)
StatisticsManager.save_global_record(global_stats_record, self.sensor_icons, route_indexer.total, args.checkpoint)
def main():
description = "CARLA AD Leaderboard Evaluation: evaluate your Agent in CARLA scenarios\n"
# general parameters
parser = argparse.ArgumentParser(description=description, formatter_class=RawTextHelpFormatter)
parser.add_argument('--host', default='localhost',
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('--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('--debug', type=int, help='Run with debug output', default=0)
parser.add_argument('--record', type=str, default='',
help='Use CARLA recording feature to create a recording of the scenario')
parser.add_argument('--timeout', default="60.0",
help='Set the CARLA client timeout value in seconds')
# simulation setup
parser.add_argument('--routes',
help='Name of the route to be executed. Point to the route_xml_file to be executed.',
required=True)
parser.add_argument('--scenarios',
help='Name of the scenario annotation file to be mixed with the route.',
required=True)
parser.add_argument('--repetitions',
type=int,
default=1,
help='Number of repetitions per route.')
# agent-related options
parser.add_argument("-a", "--agent", type=str, help="Path to Agent's py file to evaluate", required=True)
parser.add_argument("--agent-config", type=str, help="Path to Agent's configuration file", default="")
parser.add_argument("--track", type=str, default='MAP', help="Participation track: SENSORS, MAP")
parser.add_argument('--resume', type=bool, default=False, help='Resume execution from last checkpoint?')
parser.add_argument("--checkpoint", type=str,
default='./simulation_results.json',
help="Path to checkpoint used for saving statistics and resuming")
arguments = parser.parse_args()
statistics_manager = StatisticsManager()
try:
leaderboard_evaluator = LeaderboardEvaluator(arguments, statistics_manager)
leaderboard_evaluator.run(arguments)
except Exception as e:
traceback.print_exc()
finally:
del leaderboard_evaluator
if __name__ == '__main__':
main()