From 02330cd84dcd849dd9def3f51d9fa641e85520b8 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Fri, 10 Apr 2020 17:50:33 +0200 Subject: [PATCH] sumo net automatically generated --- Co-Simulation/Sumo/run_synchronization.py | 20 ++-- Co-Simulation/Sumo/spawn_npc_sumo.py | 113 ++++++++---------- .../Sumo/sumo_integration/carla_simulation.py | 7 +- .../Sumo/sumo_integration/sumo_simulation.py | 47 ++++++-- Co-Simulation/Sumo/util/__init__.py | 0 Co-Simulation/Sumo/util/netconvert_carla.py | 53 ++++---- 6 files changed, 129 insertions(+), 111 deletions(-) create mode 100644 Co-Simulation/Sumo/util/__init__.py diff --git a/Co-Simulation/Sumo/run_synchronization.py b/Co-Simulation/Sumo/run_synchronization.py index ee9ef6223..7a94bb207 100644 --- a/Co-Simulation/Sumo/run_synchronization.py +++ b/Co-Simulation/Sumo/run_synchronization.py @@ -87,6 +87,12 @@ class SimulationSynchronization(object): BridgeHelper.blueprint_library = self.carla.world.get_blueprint_library() BridgeHelper.offset = self.sumo.get_net_offset() + # Configuring carla simulation in sync mode. + settings = self.carla.world.get_settings() + settings.synchronous_mode = True + settings.fixed_delta_seconds = self.carla.step_length + self.carla.world.apply_settings(settings) + def tick(self): """ Tick to simulation synchronization @@ -225,8 +231,8 @@ def synchronization_loop(args): Entry point for sumo-carla co-simulation. """ try: - sumo_simulation = SumoSimulation(args.sumo_host, args.sumo_port, args.step_length, - args.sumo_cfg_file, args.sumo_gui) + sumo_simulation = SumoSimulation(args.sumo_cfg_file, args.step_length, args.sumo_host, + args.sumo_port, args.sumo_gui) carla_simulation = CarlaSimulation(args.carla_host, args.carla_port, args.step_length) synchronization = SimulationSynchronization(sumo_simulation, carla_simulation, @@ -254,6 +260,7 @@ def synchronization_loop(args): if __name__ == '__main__': argparser = argparse.ArgumentParser(description=__doc__) + argparser.add_argument('sumo_cfg_file', type=str, help='sumo configuration file') argparser.add_argument('--carla-host', metavar='H', default='127.0.0.1', @@ -272,14 +279,7 @@ if __name__ == '__main__': default=None, type=int, help='TCP port to liston to (default: 8813)') - argparser.add_argument('-c', - '--sumo-cfg-file', - default=None, - type=str, - help='sumo configuration file') - argparser.add_argument('--sumo-gui', - action='store_true', - help='run the gui version of sumo') + argparser.add_argument('--sumo-gui', action='store_true', help='run the gui version of sumo') argparser.add_argument('--step-length', default=0.05, type=float, diff --git a/Co-Simulation/Sumo/spawn_npc_sumo.py b/Co-Simulation/Sumo/spawn_npc_sumo.py index c8d5c90ab..5e160dbab 100644 --- a/Co-Simulation/Sumo/spawn_npc_sumo.py +++ b/Co-Simulation/Sumo/spawn_npc_sumo.py @@ -12,13 +12,13 @@ # ================================================================================================== import argparse -import datetime import json import logging -import time import random import re import shutil +import tempfile +import time import lxml.etree as ET # pylint: disable=wrong-import-position @@ -59,16 +59,17 @@ from sumo_integration.sumo_simulation import SumoSimulation # pylint: disable=w from run_synchronization import SimulationSynchronization # pylint: disable=wrong-import-position +from util.netconvert_carla import netconvert_carla + # ================================================================================================== # -- main ------------------------------------------------------------------------------------------ # ================================================================================================== -def write_sumocfg_xml(town_name, tmp_path, net_file, vtypes_file, viewsettings_file): +def write_sumocfg_xml(cfg_file, net_file, vtypes_file, viewsettings_file): """ Writes sumo configuration xml file. """ - root = ET.Element('configuration') input_tag = ET.SubElement(root, 'input') @@ -79,58 +80,51 @@ def write_sumocfg_xml(town_name, tmp_path, net_file, vtypes_file, viewsettings_f ET.SubElement(gui_tag, 'gui-settings-file', {'value': viewsettings_file}) tree = ET.ElementTree(root) - filename = os.path.join(tmp_path, town_name + '.sumocfg') - tree.write(filename, pretty_print=True, encoding='UTF-8', xml_declaration=True) - - return filename - - -def get_sumo_files(town_name, tmp_path): - """ - Returns sumo configuration file and sumo net. - """ - base_path = os.path.dirname(os.path.realpath(__file__)) - net_file = os.path.join(base_path, 'examples', 'net', town_name + '.net.xml') - vtypes_file = os.path.join(base_path, 'examples', 'carlavtypes.rou.xml') - viewsettings_file = os.path.join(base_path, 'examples', 'viewsettings.xml') - - cfg_file = write_sumocfg_xml(town_name, tmp_path, net_file, vtypes_file, viewsettings_file) - return cfg_file, net_file + tree.write(cfg_file, pretty_print=True, encoding='UTF-8', xml_declaration=True) def main(args): - # Creating temporal folder to save configuration file. - tmp_path = 'spawn_npc_sumo-{date:%Y-%m-%d_%H-%M-%S-%f}'.format(date=datetime.datetime.now()) - if not os.path.exists(tmp_path): - os.mkdir(tmp_path) + # Temporal folder to save intermediate files. + tmpdir = tempfile.mkdtemp() + + # ---------------- + # carla simulation + # ---------------- + carla_simulation = CarlaSimulation(args.host, args.port, args.step_length) + + world = carla_simulation.client.get_world() + current_map = carla_simulation.client.get_world().get_map() + + xodr_file = os.path.join(tmpdir, current_map.name + '.xodr') + current_map.save_to_disk(xodr_file) + + # --------------- + # sumo simulation + # --------------- + net_file = os.path.join(tmpdir, current_map.name + '.net.xml') + netconvert_carla(xodr_file, net_file, guess_tls=True) + + basedir = os.path.dirname(os.path.realpath(__file__)) + cfg_file = os.path.join(tmpdir, current_map.name + '.sumocfg') + vtypes_file = os.path.join(basedir, 'examples', 'carlavtypes.rou.xml') + viewsettings_file = os.path.join(basedir, 'examples', 'viewsettings.xml') + write_sumocfg_xml(cfg_file, net_file, vtypes_file, viewsettings_file) + + sumo_net = sumolib.net.readNet(net_file) + sumo_simulation = SumoSimulation(cfg_file, + args.step_length, + host=None, + port=None, + sumo_gui=args.sumo_gui) + + # --------------- + # synchronization + # --------------- + synchronization = SimulationSynchronization(sumo_simulation, carla_simulation, args.tls_manager, + args.sync_vehicle_color, args.sync_vehicle_lights) try: - # ---------------- - # carla simulation - # ---------------- - carla_simulation = CarlaSimulation(args.host, args.port, args.step_length) - - world = carla_simulation.client.get_world() - current_map = world.get_map().name - if current_map not in ('Town01', 'Town04', 'Town05'): - raise RuntimeError('This script does not support {} yet.'.format(current_map)) - - # --------------- - # sumo simulation - # --------------- - cfg_file, net_file = get_sumo_files(current_map, tmp_path) - - sumo_net = sumolib.net.readNet(net_file) - sumo_simulation = SumoSimulation(None, None, args.step_length, cfg_file, args.sumo_gui) - - # --------------- - # synchronization - # --------------- - synchronization = SimulationSynchronization(sumo_simulation, carla_simulation, - args.tls_manager, args.sync_vehicle_color, - args.sync_vehicle_lights) - # ---------- # Blueprints # ---------- @@ -183,10 +177,12 @@ def main(args): if index == (len(route) - 1): current_edge = sumo_net.getEdge(route[index]) - next_edge = random.choice(list(current_edge.getAllowedOutgoing(vclass).keys())) + available_edges = list(current_edge.getAllowedOutgoing(vclass).keys()) + if available_edges: + next_edge = random.choice(available_edges) - new_route = [current_edge.getID(), next_edge.getID()] - traci.vehicle.setRoute(vehicle_id, new_route) + new_route = [current_edge.getID(), next_edge.getID()] + traci.vehicle.setRoute(vehicle_id, new_route) end = time.time() elapsed = end - start @@ -197,10 +193,9 @@ def main(args): logging.info('Cancelled by user.') finally: - if os.path.exists(tmp_path): - shutil.rmtree(tmp_path) + if os.path.exists(tmpdir): + shutil.rmtree(tmpdir) - logging.info('Destroying %d sumo vehicles.', traci.vehicle.getIDCount()) synchronization.close() @@ -239,9 +234,7 @@ if __name__ == '__main__': metavar='PATTERN', default='walker.pedestrian.*', help='pedestrians filter (default: "walker.pedestrian.*")') - argparser.add_argument('--sumo-gui', - action='store_true', - help='run the gui version of sumo') + argparser.add_argument('--sumo-gui', action='store_true', help='run the gui version of sumo') argparser.add_argument('--step-length', default=0.05, type=float, @@ -272,4 +265,4 @@ if __name__ == '__main__': else: logging.basicConfig(format='%(levelname)s: %(message)s', level=logging.INFO) - main(args) + main(args) \ No newline at end of file diff --git a/Co-Simulation/Sumo/sumo_integration/carla_simulation.py b/Co-Simulation/Sumo/sumo_integration/carla_simulation.py index 3a2652ad5..19a15999d 100644 --- a/Co-Simulation/Sumo/sumo_integration/carla_simulation.py +++ b/Co-Simulation/Sumo/sumo_integration/carla_simulation.py @@ -32,12 +32,7 @@ class CarlaSimulation(object): self.world = self.client.get_world() self.blueprint_library = self.world.get_blueprint_library() - - # Configuring carla simulation in sync mode. - settings = self.world.get_settings() - settings.synchronous_mode = True - settings.fixed_delta_seconds = step_length - self.world.apply_settings(settings) + self.step_length = step_length # The following sets contain updated information for the current frame. self._active_actors = set() diff --git a/Co-Simulation/Sumo/sumo_integration/sumo_simulation.py b/Co-Simulation/Sumo/sumo_integration/sumo_simulation.py index ab667189e..fbbca0da8 100644 --- a/Co-Simulation/Sumo/sumo_integration/sumo_simulation.py +++ b/Co-Simulation/Sumo/sumo_integration/sumo_simulation.py @@ -14,6 +14,7 @@ import collections import enum import logging +import os import carla # pylint: disable=import-error import sumolib # pylint: disable=import-error @@ -21,6 +22,8 @@ import traci # pylint: disable=import-error from .constants import INVALID_ACTOR_ID +import lxml.etree as ET # pylint: disable=import-error + # ================================================================================================== # -- sumo definitions ------------------------------------------------------------------------------ # ================================================================================================== @@ -99,7 +102,7 @@ class SumoActorClass(enum.Enum): SumoActor = collections.namedtuple('SumoActor', 'type_id vclass transform signals extent color') # ================================================================================================== -# -- sumo simulation ------------------------------------------------------------------------------- +# -- sumo traffic lights --------------------------------------------------------------------------- # ================================================================================================== @@ -277,11 +280,35 @@ class SumoTLManager(object): self._current_phase[tl_id] = current_phase +# ================================================================================================== +# -- sumo simulation ------------------------------------------------------------------------------- +# ================================================================================================== + +def _get_sumo_net(cfg_file): + """ + Returns sumo net. + + This method reads the sumo configuration file and retrieve the sumo net filename to create the + net. + """ + cfg_file = os.path.join(os.getcwd(), cfg_file) + + tree = ET.parse(cfg_file) + tag = tree.find('//net-file') + if tag is None: + return None + + net_file = os.path.join(os.path.dirname(cfg_file), tag.get('value')) + logging.debug('Reading net file: %s', net_file) + + sumo_net = traci.sumolib.net.readNet(net_file) + return sumo_net + class SumoSimulation(object): """ SumoSimulation is responsible for the management of the sumo simulation. """ - def __init__(self, host, port, step_length, cfg_file, sumo_gui=False): + def __init__(self, cfg_file, step_length, host=None, port=None, sumo_gui=False): if sumo_gui is True: sumo_binary = sumolib.checkBinary('sumo-gui') else: @@ -303,6 +330,9 @@ class SumoSimulation(object): logging.info('Connection to sumo server. Host: %s Port: %s', host, port) traci.init(host=host, port=port) + # Retrieving net from configuration file. + self.net = _get_sumo_net(cfg_file) + # Creating a random route to be able to spawn carla actors. traci.route.add("carla_route", [traci.edge.getIDList()[0]]) @@ -349,20 +379,11 @@ class SumoSimulation(object): """ traci.vehicle.unsubscribe(actor_id) - @staticmethod - def get_net_offset(): + def get_net_offset(self): """ Accessor for sumo net offset. """ - offset = traci.simulation.convertGeo(0, 0) - return (-offset[0], -offset[1]) - - @staticmethod - def get_step_length(): - """ - Accessor for sumo simulation step length. - """ - return traci.simulation.getDeltaT() + return self.net.getLocationOffset() @staticmethod def get_actor(actor_id): diff --git a/Co-Simulation/Sumo/util/__init__.py b/Co-Simulation/Sumo/util/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/Co-Simulation/Sumo/util/netconvert_carla.py b/Co-Simulation/Sumo/util/netconvert_carla.py index 85fa2ab1e..e24d6f08d 100644 --- a/Co-Simulation/Sumo/util/netconvert_carla.py +++ b/Co-Simulation/Sumo/util/netconvert_carla.py @@ -17,10 +17,10 @@ the net and inserts, manually, the traffic light landmarks retrieved from the op import argparse import bisect import collections -import datetime import logging import shutil import subprocess +import tempfile import lxml.etree as ET # pylint: disable=import-error @@ -362,29 +362,30 @@ class SumoTrafficLight(object): # ================================================================================================== -def netconvert_carla(args, tmp_path): +def _netconvert_carla_impl(xodr_file, output, tmpdir, guess_tls=False): """ - Generates sumo net. + Implements netconvert carla. """ # ---------- # netconvert # ---------- - tmp_file = os.path.splitext(os.path.basename(args.xodr_file))[0] - tmp_sumo_net = os.path.join(tmp_path, tmp_file + '.net.xml') + basename = os.path.splitext(os.path.basename(xodr_file))[0] + tmp_sumo_net = os.path.join(tmpdir, basename + '.net.xml') try: + basedir = os.path.dirname(os.path.realpath(__file__)) result = subprocess.call(['netconvert', - '--opendrive', args.xodr_file, + '--opendrive', xodr_file, '--output-file', tmp_sumo_net, '--geometry.min-radius.fix', '--geometry.remove', '--opendrive.curve-resolution', '1', '--opendrive.import-all-lanes', - '--type-files', 'data/opendrive_netconvert.typ.xml', + '--type-files', os.path.join(basedir, 'data/opendrive_netconvert.typ.xml'), # Necessary to link odr and sumo ids. '--output.original-names', # Discard loading traffic lights as them will be inserted manually afterwards. - '--tls.discard-loaded', 'true' + '--tls.discard-loaded', 'true', ]) except subprocess.CalledProcessError: raise RuntimeError('There was an error when executing netconvert.') @@ -401,7 +402,7 @@ def netconvert_carla(args, tmp_path): # --------- # Carla map # --------- - with open(args.xodr_file, 'r') as f: + with open(xodr_file, 'r') as f: carla_map = carla.Map('netconvert', str(f.read())) # --------- @@ -437,7 +438,7 @@ def netconvert_carla(args, tmp_path): tls[tlid] = SumoTrafficLight(tlid) tl = tls[tlid] - if args.guess_tls: + if guess_tls: for from_edge, from_lane in sumo_topology.get_incoming(road_id, lane_id): successors = sumo_topology.get_successors(from_edge, from_lane) for to_edge, to_lane in successors: @@ -503,25 +504,33 @@ def netconvert_carla(args, tmp_path): connection.from_road, connection.to_road, connection.from_lane, connection.to_lane)) - tree.write(args.output, pretty_print=True, encoding='UTF-8', xml_declaration=True) + tree.write(output, pretty_print=True, encoding='UTF-8', xml_declaration=True) + +def netconvert_carla(xodr_file, output, guess_tls=False): + """ + Generates sumo net. + + :param xodr_file: opendrive file (*.xodr) + :param output: output file (*.net.xml) + :param guess_tls: guess traffic lights at intersections. + :returns: path to the generated sumo net. + """ + try: + tmpdir = tempfile.mkdtemp() + _netconvert_carla_impl(xodr_file, output, tmpdir, guess_tls) + + finally: + if os.path.exists(tmpdir): + shutil.rmtree(tmpdir) if __name__ == '__main__': argparser = argparse.ArgumentParser(description=__doc__) - argparser.add_argument('xodr_file', help='open drive file (*.xodr') + argparser.add_argument('xodr_file', help='opendrive file (*.xodr') argparser.add_argument('--output', '-o', type=str, help='output file (*.net.xml)') argparser.add_argument('--guess-tls', action='store_true', help='guess traffic lights at intersections (default: False)') args = argparser.parse_args() - try: - tmp_path = 'tmp-{date:%Y-%m-%d_%H-%M-%S-%f}'.format(date=datetime.datetime.now()) - if not os.path.exists(tmp_path): - os.mkdir(tmp_path) - - netconvert_carla(args, tmp_path) - - finally: - if os.path.exists(tmp_path): - shutil.rmtree(tmp_path) \ No newline at end of file + netconvert_carla(args.xodr_file, args.output, args.guess_tls)