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.
lanelet::MapConformer Namespace Reference

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...
 

Detailed Description

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.

Function Documentation

◆ ensureCompliance()

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.

Parameters
mapA pointer to the map which will be modified in place
config_limitA value corresponding to the configurable speed limit value

Definition at line 550 of file MapConformer.cpp.

551{
552
553 auto default_traffic_rules = getAllGermanTrafficRules(); // Use german traffic rules as default as they most closely
554 // match the generic traffic rules
555 // Handle lanelets
556 for (auto lanelet : map->laneletLayer)
557 {
558 addInferredAccessRule(lanelet, map, default_traffic_rules);
560 addInferredDirectionOfTravel(lanelet, map, default_traffic_rules);
561 addValidSpeedLimit(lanelet, map, config_limit, default_traffic_rules);// 0_mph can be changed with the config_limit
562
563
564 }
565 // Handle areas
566 for (auto area : map->areaLayer)
567 {
568 addInferredAccessRule(area, map, default_traffic_rules);
570 }
571}
std::vector< lanelet::traffic_rules::TrafficRulesUPtr > getAllGermanTrafficRules()
Helper function to return the set of all german traffic rules which are currently implemented.
void addInferredDirectionOfTravel(Lanelet &lanelet, lanelet::LaneletMapPtr map, const std::vector< lanelet::traffic_rules::TrafficRulesUPtr > &default_traffic_rules)
Generate DirectionOfTravel from the inferred regulations in the provided map and lanelet Only adds a ...
void addValidSpeedLimit(Lanelet &lanelet, lanelet::LaneletMapPtr map, lanelet::Velocity config_limit, const std::vector< lanelet::traffic_rules::TrafficRulesUPtr > &default_traffic_rules)
void addInferredPassingControlLine(Area &area, lanelet::LaneletMapPtr map)
Generate PassingControlLines from the inferred regulations in the provided map and area.
void addInferredAccessRule(Area &area, lanelet::LaneletMapPtr map, const std::vector< lanelet::traffic_rules::TrafficRulesUPtr > &default_traffic_rules)
Generate RegionAccessRules from the inferred regulations in the provided map and area.

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().

Here is the call graph for this function:
Here is the caller graph for this function: