maliput_malidrive
|
Builder class on top of the xodr::DBManager
which should already have loaded the map.
It will construct a RoadGeometry that maps to the XODR description.
OpenDRIVE's format hierarchy is simple and built on top of a XML format. Details can be found in https://www.asam.net/standards/detail/opendrive/ As a shortcut, the map follows this structure:
OpenDrive
Thus, for Junction -> Segment -> Lane creation, the build process consists of visiting all the nodes and creating the equivalent entities.
To properly connect Lanes through BranchPoints, it is important to understand the logic behind road linkage first in OpenDRIVE. Road
s can be joint using Junction
s (when there is more than one option Lane
to follow) or Successor
and Predecessor
tags (when linkage is trivially solved). A Road
could be marked as part of a Junction
or not, depending if the connecting end ends in a Junction
. At the same time, outer LaneSection
s hold Lane
s that could connect to either a Junction
or another Road
. However, inner LaneSection
s hold Lane
s that can only connect to other Lane
s that belong to a consecutive LaneSection
, or end in the middle of the road. Given that, BranchPoint
s need to be solved in different stages:
LaneSection
sLaneSection
s with Junction
s / Road
s #include <src/maliput_malidrive/builder/road_geometry_builder.h>
Public Member Functions | |
RoadGeometryBuilder ()=delete | |
RoadGeometryBuilder (std::unique_ptr< xodr::DBManager > manager, const RoadGeometryConfiguration &road_geometry_configuration) | |
Builds a RoadGeometry using malidrive backend whose ID is road_geometry_configuration.id . More... | |
std::unique_ptr< const maliput::api::RoadGeometry > | operator() () |
Creates a maliput equivalent backend (malidrive::RoadGeometry). More... | |
|
delete |
RoadGeometryBuilder | ( | std::unique_ptr< xodr::DBManager > | manager, |
const RoadGeometryConfiguration & | road_geometry_configuration | ||
) |
Builds a RoadGeometry using malidrive backend whose ID is road_geometry_configuration.id
.
manager
must not be nullptr. Ownership will be transferred to the resulting RoadGeometry.
Resulting maliput::api::RoadGeometry will have properties set by the road_geometry_configuration
.
Note: the opendrive_file
parameter of road_geometry_configuration
is ignored because a manager is expected to emerge.
maliput::common::assertion_error | When road_geometry_configuration.tolerances.linear_tolerance , road_geometry_configuration.tolerances.angular_tolerance or road_geometry_configuration.scale_length are negative. |
maliput::common::assertion_error | When road_geometry_configuration.tolerances.max_linear_tolerance is less than road_geometry_configuration.tolerances.linear_tolerance . |
maliput::common::assertion_error | When manager is nullptr. |
std::unique_ptr< const maliput::api::RoadGeometry > operator() | ( | ) |
Creates a maliput equivalent backend (malidrive::RoadGeometry).
When RoadGeometryConfiguration::ToleranceSelectionPolicy::kManualSelection is used, the initial linear_tolerance, angular_tolerance and scale_length are used. Otherwise, up to constants::kAutomaticSelectionTrials + 1 trials are done with increasing linear_tolerance, angular_tolerance and scale_length equal to constants::kScaleLength. Each iteration will add a 10% to linear_tolerance and angular_tolerance.
Consider using small or default values of linear_tolerance and angular_tolerance to granularly try with different configurations.