Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
|
Namespaces | |
namespace | anonymous_namespace{MapConformer.cpp} |
Functions | |
void | ensureCompliance (lanelet::LaneletMapPtr map, lanelet::Velocity config_limit=80_mph) |
Function modifies an existing map to make a best effort attempt at ensuring the map confroms to the expectations of CarmaUSTrafficRules. More... | |
The map conformer API is responsible for ensuring that a loaded lanelet2 map meets the expectations of CarmaUsTrafficRules Rather than simply validating the map this class will actually modify the map when possible to ensure compliance. NOTE: This class is not meant to be used by carma_wm users at runtime. It is only used in WMTestLibraryForGuidance currently to support unit testing.
The map conformer is responsible for ensuring that a loaded lanelet2 map meets the expectations of CarmaUsTrafficRules Rather than simply validating the map this class will actually modify the map when possible to ensure compliance. NOTE: This class is not meant to be used by carma_wm users at runtime. It is only used in WMTestLibraryForGuidance currently to support unit testing.
void lanelet::MapConformer::ensureCompliance | ( | lanelet::LaneletMapPtr | map, |
lanelet::Velocity | config_limit = 80_mph |
||
) |
Function modifies an existing map to make a best effort attempt at ensuring the map confroms to the expectations of CarmaUSTrafficRules.
Map is updated by ensuring all lanelet and area bounds are marked with PassingControlLines In addition, lanelets and areas are updated to have their accessability marked with a RegionAccessRule. At the moment the creation of DigitalSpeedLimits for all lanelets/areas is not performed. This is because CarmaUSTrafficRules supports the existing SpeedLimit definition and allows DigitalSpeedLimits to be overlayed on that.
map | A pointer to the map which will be modified in place |
config_limit | A value corresponding to the configurable speed limit value |
Definition at line 550 of file MapConformer.cpp.
References lanelet::MapConformer::anonymous_namespace{MapConformer.cpp}::addInferredAccessRule(), lanelet::MapConformer::anonymous_namespace{MapConformer.cpp}::addInferredDirectionOfTravel(), lanelet::MapConformer::anonymous_namespace{MapConformer.cpp}::addInferredPassingControlLine(), lanelet::MapConformer::anonymous_namespace{MapConformer.cpp}::addValidSpeedLimit(), and lanelet::MapConformer::anonymous_namespace{MapConformer.cpp}::getAllGermanTrafficRules().
Referenced by carma_wm_ctrl::WMBroadcaster::baseMapCallback(), and carma_wm::test::buildGuidanceTestMap().