From 1047c76d2b38f9617f2b7fccc0124c1f540cdee6 Mon Sep 17 00:00:00 2001
From: Axel1092
Date: Thu, 23 Jul 2020 15:08:50 +0200
Subject: [PATCH] Added settings class for osm to odr conversion and
documentation.
---
Docs/python_api.md | 30 ++++++++++
PythonAPI/carla/source/libcarla/Converter.cpp | 18 ++++--
PythonAPI/docs/osm2odr.yml | 55 +++++++++++++++++++
Util/Converter/src/Converter.cpp | 22 +++++---
Util/Converter/src/Converter.h | 7 ++-
5 files changed, 117 insertions(+), 15 deletions(-)
create mode 100644 PythonAPI/docs/osm2odr.yml
diff --git a/Docs/python_api.md b/Docs/python_api.md
index 01036737d..5d16a799f 100644
--- a/Docs/python_api.md
+++ b/Docs/python_api.md
@@ -1367,6 +1367,36 @@ Returns a waypoint if all the parameters passed are correct. Otherwise, returns
---
+## carla.OSM2ODR
+Class that performs the conversion of Open Street Maps data to OpenDRIVE.
+
+Methods
+- **convert_to_odr**(**osm_file**, **settings**)
+Converts a Open Street Maps file to OpenDRIVE format using the settings provided by the second argument.
+ - **Parameters:**
+ - `osm_file` (_str_) – The input Open Street Maps xml data.
+ - `settings` (_[carla.OSM2ODRSettings](#carla.OSM2ODRSettings)_) – The settings used for the conversion.
+ - **Return:** _str_
+
+---
+
+## carla.OSM2ODRSettings
+Class containing settings to perform the conversion of Open Street Map data to OpenDRIVE.
+
+Instance Variables
+- **use_offsets** (_bool_)
+Enables the use of offset to position the map.
+- **offset_x** (_float_)
+Offset in the x axis.
+- **offset_y** (_float_)
+Offset in the y axis.
+- **default_lane_width** (_float_)
+Defines the default width of lanes.
+- **elevation_layer_height** (_float_)
+Defines the height of the different layers defined in Open Street Map data (see https://wiki.openstreetmap.org/wiki/Key:layer).
+
+---
+
## carla.ObstacleDetectionEvent
Inherited from _[carla.SensorData](#carla.SensorData)_
Class that defines the obstacle data for sensor.other.obstacle. Learn more about this [here](ref_sensors.md#obstacle-detector).
diff --git a/PythonAPI/carla/source/libcarla/Converter.cpp b/PythonAPI/carla/source/libcarla/Converter.cpp
index 156ff5eb2..7d66b3c49 100644
--- a/PythonAPI/carla/source/libcarla/Converter.cpp
+++ b/PythonAPI/carla/source/libcarla/Converter.cpp
@@ -8,19 +8,25 @@
class OSM2ODR {
public:
- static std::string ConvertOSMToOpenDRIVE(std::string osm_file) {
- return osm2odr::ConvertOSMToOpenDRIVE(osm_file);
- }
+ // static std::string ConvertOSMToOpenDRIVE(std::string osm_file, osm2odr::) {
+ // return osm2odr::ConvertOSMToOpenDRIVE(osm_file);
+ // }
};
void export_converter() {
using namespace osm2odr;
using namespace boost::python;
- // def("convert_to_odr", &ConvertOSMToOpenDRIVE, (arg("osm_file"), arg("offsetX") = 0, arg("offsetY") = 0));
+ class_("OSM2ODRSettings", init<>())
+ .add_property("use_offsets", &OSM2ODRSettings::use_offsets, &OSM2ODRSettings::use_offsets)
+ .add_property("offset_x", &OSM2ODRSettings::offset_x, &OSM2ODRSettings::offset_x)
+ .add_property("offset_y", &OSM2ODRSettings::offset_y, &OSM2ODRSettings::offset_y)
+ .add_property("default_lane_width", &OSM2ODRSettings::default_lane_width, &OSM2ODRSettings::default_lane_width)
+ .add_property("elevation_layer_height", &OSM2ODRSettings::elevation_layer_height, &OSM2ODRSettings::elevation_layer_height)
+ ;
- class_("OSM2ODR", init<>())
- .def("convert_to_odr", &OSM2ODR::ConvertOSMToOpenDRIVE, (arg("osm_file")))
+ class_("OSM2ODR", no_init)
+ .def("convert_to_odr", &ConvertOSMToOpenDRIVE, (arg("osm_file"), arg("OSM2ODRSettings") = OSM2ODRSettings()))
.staticmethod("convert_to_odr")
;
}
diff --git a/PythonAPI/docs/osm2odr.yml b/PythonAPI/docs/osm2odr.yml
new file mode 100644
index 000000000..7987b83bd
--- /dev/null
+++ b/PythonAPI/docs/osm2odr.yml
@@ -0,0 +1,55 @@
+---
+- module_name: carla
+
+ # - CLASSES ------------------------------
+ classes:
+ - class_name: OSM2ODR
+ # - DESCRIPTION ------------------------
+ doc: >
+ Class that performs the conversion of Open Street Maps data to OpenDRIVE.
+ # - METHODS ----------------------------
+ methods:
+ - def_name: convert_to_odr
+ static:
+ True
+ return: str
+ doc: >
+ The converted OpenDRIVE xml data.
+ params:
+ - param_name: osm_file
+ type: str
+ doc: >
+ The input Open Street Maps xml data.
+ - param_name: settings
+ type: carla.OSM2ODRSettings
+ doc: >
+ The settings used for the conversion.
+ doc: >
+ Converts a Open Street Maps file to OpenDRIVE format using the settings provided by the second argument.
+ # --------------------------------------
+ - class_name: OSM2ODRSettings
+ # - DESCRIPTION ------------------------
+ doc: >
+ Class containing settings to perform the conversion of Open Street Map data to OpenDRIVE.
+ # - PROPERTIES -------------------------
+ instance_variables:
+ - var_name: use_offsets
+ type: bool
+ doc: >
+ Enables the use of offset to position the map.
+ - var_name: offset_x
+ type: float
+ doc: >
+ Offset in the x axis.
+ - var_name: offset_y
+ type: float
+ doc: >
+ Offset in the y axis.
+ - var_name: default_lane_width
+ type: float
+ doc: >
+ Defines the default width of lanes.
+ - var_name: elevation_layer_height
+ type: float
+ doc: >
+ Defines the height of the different layers defined in Open Street Map data (see https://wiki.openstreetmap.org/wiki/Key:layer).
diff --git a/Util/Converter/src/Converter.cpp b/Util/Converter/src/Converter.cpp
index f0131c9cf..4e8b80130 100644
--- a/Util/Converter/src/Converter.cpp
+++ b/Util/Converter/src/Converter.cpp
@@ -66,17 +66,25 @@ namespace osm2odr {
}
std::string ConvertOSMToOpenDRIVE(std::string osm_file, OSM2ODRSettings settings) {
- // std::string OptionsArgs = "--geometry.remove --ramps.guess --edges.join --junctions.join --keep-edges.by-type highway.motorway,highway.motorway_link,highway.trunk,highway.trunk_link,highway.primary,highway.primary_link,highway.secondary,highway.secondary_link,highway.tertiary,highway.tertiary_link,highway.unclassified,highway.residential --tls.discard-loaded --tls.discard-simple --default.lanewidth 4.0 --osm.layer-elevation 4";
-
std::vector OptionsArgs = {
- "--proj", "+proj=tmerc",
+ "--simple-projection",
"--geometry.remove", "--ramps.guess", "--edges.join", "--junctions.join", "--roundabouts.guess",
- "--keep-edges.by-type", "highway.motorway,highway.motorway_link,highway.trunk,highway.trunk_link,highway.primary,highway.primary_link,highway.secondary,highway.secondary_link,highway.tertiary,highway.tertiary_link,highway.unclassified,highway.residential",
- "--tls.discard-loaded", "--tls.discard-simple", "--default.lanewidth", "4.0",
- "--osm.layer-elevation", "4",
+ "--keep-edges.by-type",
+ "highway.motorway,highway.motorway_link,highway.trunk,highway.trunk_link,highway.primary,highway.primary_link,highway.secondary,highway.secondary_link,highway.tertiary,highway.tertiary_link,highway.unclassified,highway.residential",
+ "--tls.discard-loaded", "--tls.discard-simple", "--default.lanewidth",
+ std::to_string(settings.default_lane_width),
"--osm-files", "TRUE", "--opendrive-output", "TRUE", // necessary for now to enable osm input and xodr output
- "--offset.x", std::to_string(settings.offsetX), "--offset.y", std::to_string(settings.offsetY)
};
+ if (settings.elevation_layer_height > 0) {
+ OptionsArgs.push_back("--osm.layer-elevation");
+ OptionsArgs.push_back(std::to_string(settings.elevation_layer_height));
+ }
+ if (settings.use_offsets) {
+ OptionsArgs.push_back("--offset.x");
+ OptionsArgs.push_back(std::to_string(settings.offset_x));
+ OptionsArgs.push_back("--offset.y");
+ OptionsArgs.push_back(std::to_string(settings.offset_y));
+ }
// OptionsCont::getOptions().clear();
OptionsCont& oc = OptionsCont::getOptions();
diff --git a/Util/Converter/src/Converter.h b/Util/Converter/src/Converter.h
index dba454e96..c7826200d 100644
--- a/Util/Converter/src/Converter.h
+++ b/Util/Converter/src/Converter.h
@@ -11,8 +11,11 @@
namespace osm2odr {
struct OSM2ODRSettings {
- double offsetX = 0;
- double offsetY = 0;
+ bool use_offsets = false;
+ double offset_x = 0;
+ double offset_y = 0;
+ double default_lane_width = 4.0;
+ double elevation_layer_height = 0;
};
std::string ConvertOSMToOpenDRIVE(std::string osm_file, OSM2ODRSettings settings = OSM2ODRSettings());