Added arguments to osm_to_xodr conversion example
This commit is contained in:
parent
e9330c5d61
commit
d1f6aa256e
|
@ -1,44 +1,107 @@
|
|||
""" Convert OpenStreetMap file to OpenDRIVE file. """
|
||||
|
||||
import argparse
|
||||
import glob
|
||||
import os
|
||||
import sys
|
||||
|
||||
try:
|
||||
sys.path.append(glob.glob('../carla/dist/carla-*%d.%d-%s.egg' % (
|
||||
sys.version_info.major,
|
||||
sys.version_info.minor,
|
||||
'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0])
|
||||
except IndexError:
|
||||
pass
|
||||
|
||||
import carla
|
||||
|
||||
# Read the .osm data
|
||||
with open("path/to/osm/file/map.osm", mode="r", encoding="utf-8") as osmFile:
|
||||
osm_data = osmFile.read()
|
||||
|
||||
# Define the desired settings. In this case, default values.
|
||||
settings = carla.Osm2OdrSettings()
|
||||
def convert(args):
|
||||
# Read the .osm data
|
||||
with open(args.input_path, mode="r", encoding="utf-8") as osmFile:
|
||||
osm_data = osmFile.read()
|
||||
|
||||
# Set OSM road types to export to OpenDRIVE
|
||||
settings.set_osm_way_types([
|
||||
"motorway",
|
||||
"motorway_link",
|
||||
"trunk",
|
||||
"trunk_link",
|
||||
"primary",
|
||||
"primary_link",
|
||||
"secondary",
|
||||
"secondary_link",
|
||||
"tertiary",
|
||||
"tertiary_link",
|
||||
"unclassified",
|
||||
"residential"
|
||||
])
|
||||
# Define the desired settings
|
||||
settings = carla.Osm2OdrSettings()
|
||||
|
||||
# set width of each lane by meters
|
||||
settings.default_lane_width = 6.0
|
||||
# Set OSM road types to export to OpenDRIVE
|
||||
settings.set_osm_way_types([
|
||||
"motorway",
|
||||
"motorway_link",
|
||||
"trunk",
|
||||
"trunk_link",
|
||||
"primary",
|
||||
"primary_link",
|
||||
"secondary",
|
||||
"secondary_link",
|
||||
"tertiary",
|
||||
"tertiary_link",
|
||||
"unclassified",
|
||||
"residential"
|
||||
])
|
||||
settings.default_lane_width = args.lane_width
|
||||
settings.generate_traffic_lights = args.traffic_lights
|
||||
settings.all_junctions_with_traffic_lights = args.all_junctions_lights
|
||||
settings.center_map = args.center_map
|
||||
|
||||
# enable traffic light generation from OSM data
|
||||
settings.generate_traffic_lights = True
|
||||
# Convert to .xodr
|
||||
xodr_data = carla.Osm2Odr.convert(osm_data, settings)
|
||||
|
||||
# ignore OSM traffic lights and set lights for all junctions
|
||||
settings.all_junctions_with_traffic_lights = True
|
||||
# save opendrive file
|
||||
with open(args.output_path, "w", encoding="utf-8") as xodrFile:
|
||||
xodrFile.write(xodr_data)
|
||||
|
||||
# set center of map to the origin coordinates
|
||||
settings.center_map = True
|
||||
|
||||
# Convert to .xodr
|
||||
xodr_data = carla.Osm2Odr.convert(osm_data, settings)
|
||||
def main():
|
||||
argparser = argparse.ArgumentParser(
|
||||
description=__doc__)
|
||||
argparser.add_argument(
|
||||
'-i', '--input-path',
|
||||
metavar='OSM_FILE_PATH',
|
||||
help='set the input OSM file path')
|
||||
argparser.add_argument(
|
||||
'-o', '--output-path',
|
||||
metavar='XODR_FILE_PATH',
|
||||
help='set the output XODR file path')
|
||||
argparser.add_argument(
|
||||
'--lane-width',
|
||||
default=6.0,
|
||||
help='width of each road lane in meters')
|
||||
argparser.add_argument(
|
||||
'--traffic-lights',
|
||||
default='store_true',
|
||||
help='enable traffic light generation from OSM data')
|
||||
argparser.add_argument(
|
||||
'--all-junctions-lights',
|
||||
default='store_true',
|
||||
help='set traffic lights for all junctions')
|
||||
argparser.add_argument(
|
||||
'--center-map',
|
||||
default='store_true',
|
||||
help='set center of map to the origin coordinates')
|
||||
|
||||
# save opendrive file
|
||||
with open("path/to/create/xodr/file/map.xodr", "w", encoding="utf-8") as xodrFile:
|
||||
xodrFile.write(xodr_data)
|
||||
if len(sys.argv) < 2:
|
||||
argparser.print_help()
|
||||
return
|
||||
|
||||
args = argparser.parse_args()
|
||||
|
||||
if args.input_path is None or not os.path.exists(args.input_path):
|
||||
print('input file not found.')
|
||||
if args.output_path is None:
|
||||
print('output file path not found.')
|
||||
|
||||
try:
|
||||
convert()
|
||||
except:
|
||||
print('\nAn error has occurred in conversion.')
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
||||
try:
|
||||
main()
|
||||
except KeyboardInterrupt:
|
||||
print('\nCancelled by user. Bye!')
|
||||
except RuntimeError as e:
|
||||
print(e)
|
||||
|
|
Loading…
Reference in New Issue