carla/Docs/tuto_G_openstreetmap.md

115 lines
5.9 KiB
Markdown
Raw Normal View History

# Generate maps with OpenStreetMap
2020-07-24 00:46:20 +08:00
2020-07-30 04:37:14 +08:00
OpenStreetMap is an open license map of the world developed by contributors. Sections of these map can be exported to a `.osm` file, the OpenSreetMap format, which is essentially an XML. CARLA can convert this file to OpenDRIVE format and ingest it as any other OpenDRIVE map using the [OpenDRIVE Standalone Mode](#adv_opendrive.md). The process is quite straightforward.
2020-07-24 00:46:20 +08:00
2020-07-29 00:40:21 +08:00
* [__1- Obtain a map with OpenStreetMap__](#1-obtain-a-map-with-openstreetmap)
2020-07-30 04:37:14 +08:00
* [__2- Convert to OpenDRIVE format__](#2-convert-to-opendrive-format)
2020-07-29 00:40:21 +08:00
* [__3- Import into CARLA__](#3-import-into-carla)
2020-07-24 00:46:20 +08:00
---
2020-07-29 00:40:21 +08:00
## 1- Obtain a map with OpenStreetMap
2020-07-24 00:46:20 +08:00
2020-07-30 04:37:14 +08:00
The first thing to do is use [OpenStreetMap](https://www.openstreetmap.org) to generate the file containing the map information.
2020-07-24 00:46:20 +08:00
2020-07-29 20:27:20 +08:00
__1.1. Go to [openstreetmap.org](https://www.openstreetmap.org)__. If the map is not properly visualized, try changing the layer in the righ pannel.
2020-07-24 00:46:20 +08:00
2020-07-29 00:40:21 +08:00
__1.2 Search for a desired location__ and zoom in to a specific area.
![openstreetmap_view](img/tuto_g_osm_web.jpg)
2020-07-24 00:46:20 +08:00
!!! Warning
2020-07-30 04:37:14 +08:00
Due to the Unreal Engine limitations, CARLA can ingest maps of a limited size (large cities like Paris push the limits of the engine). Additionally, the bigger the map, the longer the conversion to OpenDRIVE will take.
2020-07-24 00:46:20 +08:00
2020-07-29 00:40:21 +08:00
__1.3.Click on `Export`__ in the upper left side of the window. The __Export__ pannel will open.
2020-07-24 00:46:20 +08:00
2020-07-29 00:40:21 +08:00
__1.4. Click on `Manually select a different area`__ in the __Export__ pannel.
2020-07-24 00:46:20 +08:00
2020-07-29 00:40:21 +08:00
__1.5. Select a custom area__ by dragging the corners of the square area in the viewport.
2020-07-24 00:46:20 +08:00
2020-07-30 04:37:14 +08:00
__1.6. Click the `Export` button__ in the __Export__ pannel, and save the map information of the selected area as a `.osm` file.
2020-07-24 00:46:20 +08:00
2020-07-29 00:40:21 +08:00
![openstreetmap_area](img/tuto_g_osm_area.jpg)
2020-07-24 00:46:20 +08:00
---
2020-07-29 00:40:21 +08:00
## 2- Convert to OpenDRIVE format
2020-07-24 00:46:20 +08:00
2020-07-30 04:37:14 +08:00
CARLA can read a the content in the `.osm` file generated with OpenStreetMap, and convert it to OpenDRIVE format so that it can be ingested as a CARLA map. This can be done using the following classes in the PythonAPI.
2020-07-29 20:27:20 +08:00
* __[carla.Osm2Odr](python_api.md#carla.Osm2Odr)__ The class that does the conversion. It takes the content of the `.osm` parsed as strind, and returns a string containing the resulting `.xodr`.
* `osm_file` — The content of the initial `.osm` file parsed as string.
* `settings` — A [carla.Osm2OdrSettings](python_api.md#carla.Osm2OdrSettings) object containing the settings to parameterize the conversion.
* __[carla.Osm2OdrSettings](python_api.md#carla.Osm2OdrSettings)__ Helper class that contains different parameters used during the conversion.
* `use_offsets` *(default False)* — Determines whereas the map should be generated with an offset, thus moving the origin from the center according to that offset.
* `offset_x` *(default 0.0)* — Offset in the X axis.
* `offset_y` *(default 0.0)* — Offset in the Y axis.
* `default_lane_width` *(default 4.0)* — Determines the width that lanes should have in the resulting XODR file.
* `elevation_layer_height` *(default 0.0)* — Determines the height separating elements in different layers, used for overlapping elements. Read more on [layers](https://wiki.openstreetmap.org/wiki/Key:layer).
2020-07-29 20:27:20 +08:00
The input and output of the conversion are not the `.osm` and `.xodr` files itself, but their content. For said reason, the code should be similar to the following.
2020-07-29 00:40:21 +08:00
```
# Read the .osm data
f = open("path/to/osm/file", 'r')
osm_data = f.read()
2020-07-29 00:40:21 +08:00
f.close()
2020-07-29 20:27:20 +08:00
# Define the desired settings. In this case, default values.
2020-07-29 00:40:21 +08:00
settings = carla.Osm2OdrSettings()
# Convert to .xodr
2020-07-29 20:27:20 +08:00
xodr_data = carla.Osm2Odr.convert(osm_data, settings)
2020-07-29 00:40:21 +08:00
# save opendrive file
f = open("path/to/output/file", 'w')
f.write(xodr_data)
2020-07-29 00:40:21 +08:00
f.close()
```
2020-07-29 20:27:20 +08:00
The resulting file contains the road information in OpenDRIVE format.
2020-07-24 00:46:20 +08:00
---
## 3- Import into CARLA
2020-07-29 20:27:20 +08:00
Finally, the OpenDRIVE file can be easily ingested in CARLA using the [OpenDRIVE Standalone Mode](#adv_opendrive.md).
2020-07-24 00:46:20 +08:00
2020-07-30 04:37:14 +08:00
__a) Using your own script__ — Call for [`client.generate_opendrive_world()`](python_api.md#carla.Client.generate_opendrive_world) through the API. This will generate the new map, and block the simulation until it is ready.
Use the [carla.OpendriveGenerationParameters](python_api.md#carla.OpendriveGenerationParameters) class to set the parameterization of the mesh generation.
2020-07-24 00:46:20 +08:00
```
2020-07-29 00:40:21 +08:00
vertex_distance = 2.0 # in meters
max_road_length = 500.0 # in meters
wall_height = 0.0 # in meters
extra_width = 0.6 # in meters
world = client.generate_opendrive_world(
xodr_xml, carla.OpendriveGenerationParameters(
vertex_distance=vertex_distance,
max_road_length=max_road_length,
wall_height=wall_height,
additional_width=extra_width,
smooth_junctions=True,
enable_mesh_visibility=True))
```
!!! Note
2020-07-29 20:27:20 +08:00
`wall_height = 0.0` is strongly recommended. OpenStreetMap defines lanes in opposing directions as different roads. If walls are generated, this result in wall overlapping and undesired collisions.
2020-07-24 00:46:20 +08:00
2020-07-30 04:37:14 +08:00
__b) Using `config.py`__ — The script can load an OpenStreetMap file directly into CARLA using a new argument.
2020-07-29 00:40:21 +08:00
```
2020-09-09 22:48:04 +08:00
python3 config.py --osm-file=/path/to/OSM/file
2020-07-29 00:40:21 +08:00
```
2020-07-24 00:46:20 +08:00
!!! Warning
2020-07-30 04:37:14 +08:00
[client.generate_opendrive_world()](python_api.md#carla.Client.generate_opendrive_world) requires the __content of the OpenDRIVE file parsed as string__, and allows parameterization. On the contrary, __`config.py`__ script needs __the path to the `.xodr` file__ and always uses default parameters.
2020-07-29 00:40:21 +08:00
Either way, the map should be ingested automatically in CARLA and the result should be similar to this.
![opendrive_meshissue](img/tuto_g_osm_carla.jpg)
<div style="text-align: right"><i>Outcome of the CARLA map generation using OpenStreetMap.</i></div>
2020-07-24 00:46:20 +08:00
---
2020-07-29 00:40:21 +08:00
That is all there is to know about how to use OpenStreetMap to generate CARLA maps.
2020-07-24 00:46:20 +08:00
2020-07-29 00:40:21 +08:00
For issues and doubts related with this topic can be posted in the CARLA forum.
2020-07-24 00:46:20 +08:00
<div class="build-buttons">
<p>
<a href="https://forum.carla.org/" target="_blank" class="btn btn-neutral" title="Go to the CARLA forum">
CARLA forum</a>
</p>
</div>