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::anonymous_namespace{MapConformer.cpp} Namespace Reference

Enumerations

enum class  LaneChangeType { ToRight , ToLeft , Both , None }
 

Functions

std::vector< lanelet::traffic_rules::TrafficRulesUPtr > getAllGermanTrafficRules ()
 Helper function to return the set of all german traffic rules which are currently implemented. More...
 
template<typename Map , typename Key , typename Value >
Value getMapOrDefault (const Map &map, Key key, Value defaultVal)
 Helper function to get a value from a map or return a default value when key is not present. More...
 
bool startswith (const std::string &str, const std::string &substr)
 Helper function to check if a string starts with another string. More...
 
LaneChangeType getChangeType (const std::string &type, const std::string &subtype, const std::string &participant)
 Helper function to determine the type of lane change implicitly allowed by the markings on the road. More...
 
PassingControlLinePtr buildControlLine (LineString3d &bound, const LaneChangeType type, const std::string &participant)
 Helper function constructs a PassingControlLine based off the provided bound and lane change type. More...
 
void addInferredAccessRule (Lanelet &lanelet, lanelet::LaneletMapPtr map, const std::vector< lanelet::traffic_rules::TrafficRulesUPtr > &default_traffic_rules)
 Generate RegionAccessRules from the inferred regulations in the provided map and lanelet. More...
 
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. More...
 
void addInferredPassingControlLine (Lanelet &lanelet, lanelet::LaneletMapPtr map)
 Generate PassingControlLines from the inferred regulations in the provided map and lanelet. More...
 
void addInferredPassingControlLine (Area &area, lanelet::LaneletMapPtr map)
 Generate PassingControlLines from the inferred regulations in the provided map and area. More...
 
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 regulatory element if the direction of travel is not one_way as that is the default. More...
 
void addValidSpeedLimit (Lanelet &lanelet, lanelet::LaneletMapPtr map, lanelet::Velocity config_limit, const std::vector< lanelet::traffic_rules::TrafficRulesUPtr > &default_traffic_rules)
 

Variables

constexpr size_t PARTICIPANT_COUNT = 12
 
constexpr const char * participant_types [PARTICIPANT_COUNT]
 

Enumeration Type Documentation

◆ LaneChangeType

Function Documentation

◆ addInferredAccessRule() [1/2]

void lanelet::MapConformer::anonymous_namespace{MapConformer.cpp}::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.

Parameters
areaThe area to generate the rules for
mapThe map which the area is part of
default_traffic_rulesThe set of traffic rules to treat as guidance for interpreting the map

Definition at line 278 of file MapConformer.cpp.

280{
281 auto access_rules = area.regulatoryElementsAs<RegionAccessRule>();
282 // If the lanelet does not have an access rule then add one based on the generic traffic rules
283 if (access_rules.size() == 0)
284 { // No access rule detected so add one
285
286 // We want to check for all participants which are currently supported
287 std::vector<std::string> allowed_participants;
288
289 for (const auto& rules : default_traffic_rules)
290 {
291 if (rules->canPass(area))
292 {
293 allowed_participants.emplace_back(rules->participant());
294 }
295 }
296
297 std::shared_ptr<RegionAccessRule> rar(
298 new RegionAccessRule(RegionAccessRule::buildData(lanelet::utils::getId(), {}, { area }, allowed_participants)));
299 area.addRegulatoryElement(rar);
300 map->add(rar);
301 }
302}

Referenced by lanelet::MapConformer::ensureCompliance().

Here is the caller graph for this function:

◆ addInferredAccessRule() [2/2]

void lanelet::MapConformer::anonymous_namespace{MapConformer.cpp}::addInferredAccessRule ( Lanelet &  lanelet,
lanelet::LaneletMapPtr  map,
const std::vector< lanelet::traffic_rules::TrafficRulesUPtr > &  default_traffic_rules 
)

Generate RegionAccessRules from the inferred regulations in the provided map and lanelet.

Parameters
laneletThe lanelet to generate the rules for
mapThe map which the lanelet is part of
default_traffic_rulesThe set of traffic rules to treat as guidance for interpreting the map

Definition at line 245 of file MapConformer.cpp.

247{
248 auto access_rules = lanelet.regulatoryElementsAs<RegionAccessRule>();
249 // If the lanelet does not have an access rule then add one based on the generic traffic rules
250 if (access_rules.size() == 0)
251 { // No access rule detected so add one
252
253 // We want to check for all participants which are currently supported
254 std::vector<std::string> allowed_participants;
255
256 for (const auto& rules : default_traffic_rules)
257 {
258 if (rules->canPass(lanelet))
259 {
260 allowed_participants.emplace_back(rules->participant());
261 }
262 }
263
264 std::shared_ptr<RegionAccessRule> rar(new RegionAccessRule(
265 RegionAccessRule::buildData(lanelet::utils::getId(), { lanelet }, {}, allowed_participants)));
266 lanelet.addRegulatoryElement(rar);
267 map->add(rar);
268 }
269}

◆ addInferredDirectionOfTravel()

void lanelet::MapConformer::anonymous_namespace{MapConformer.cpp}::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 regulatory element if the direction of travel is not one_way as that is the default.

Parameters
laneletThe lanelet to generate directions of travel for
mapThe map which the lanelet is part of
default_traffic_rulesThe set of traffic rules to treat as guidance for interpreting the map

Definition at line 452 of file MapConformer.cpp.

454{
455 auto direction_of_travel = lanelet.regulatoryElementsAs<DirectionOfTravel>();
456 // If the lanelet does not have an access rule then add one based on the generic traffic rules
457 if (direction_of_travel.size() == 0)
458 { // No direction detected so need to check if one is required
459
460 // We want to check for all participants which are currently supported
461 std::vector<std::string> allowed_participants;
462
463 for (const auto& rules : default_traffic_rules)
464 {
465 if (!rules->isOneWay(lanelet))
466 { // Check if this lanelet is not oneway
467 allowed_participants.emplace_back(rules->participant());
468 }
469 }
470
471 if (allowed_participants.size() > 0)
472 { // Only add bi-directional regulations
473 std::shared_ptr<DirectionOfTravel> rar(new DirectionOfTravel(DirectionOfTravel::buildData(
474 lanelet::utils::getId(), { lanelet }, DirectionOfTravel::BiDirectional, allowed_participants)));
475 lanelet.addRegulatoryElement(rar);
476 map->add(rar);
477 }
478 }
479}

Referenced by lanelet::MapConformer::ensureCompliance().

Here is the caller graph for this function:

◆ addInferredPassingControlLine() [1/2]

void lanelet::MapConformer::anonymous_namespace{MapConformer.cpp}::addInferredPassingControlLine ( Area &  area,
lanelet::LaneletMapPtr  map 
)

Generate PassingControlLines from the inferred regulations in the provided map and area.

Parameters
areaThe area to generate control lines for
mapThe map which the area is part of

Definition at line 386 of file MapConformer.cpp.

387{
388 // Since this class is only designed to add passing control lines based on lane changes
389 // we will always assume the participant is a vehicle
390 std::string participant(lanelet::Participants::Vehicle);
391
392 LineStrings3d outerBounds = area.outerBound();
393
394 auto local_control_lines = area.regulatoryElementsAs<PassingControlLine>();
395
396 std::vector<size_t> found_indices;
397
398 // Iterate over all regulatory elements in the map to determine if there is an existing regulation for this area's
399 // bounds
400 for (auto reg_elem : map->regulatoryElementLayer)
401 {
402 if (reg_elem->attribute(AttributeName::Subtype).value() == PassingControlLine::RuleName)
403 {
404 auto pcl = std::static_pointer_cast<PassingControlLine>(reg_elem);
405 for (auto sub_line : pcl->controlLine())
406 {
407 size_t i = 0;
408 for (auto sub_bound : outerBounds)
409 {
410 if (sub_bound.id() == sub_line.id())
411 {
412 found_indices.push_back(i);
413 // If an existing regulation applies to this area's bounds then add it to the area
414 bool alreadyAdded = lanelet::utils::contains(local_control_lines, pcl);
415 if (!alreadyAdded)
416 {
417 area.addRegulatoryElement(pcl);
418 }
419 }
420 }
421 }
422 }
423 }
424
425 // For all the bounds which did not have an existing regulation create a new one
426 size_t i = 0;
427 for (auto sub_bound : outerBounds)
428 {
429 if (lanelet::utils::contains(found_indices, i))
430 {
431 continue; // Continue if this sub_bound is already accounted for
432 }
433
434 LaneChangeType change_type = getChangeType(sub_bound.attribute(AttributeName::Type).value(),
435 sub_bound.attribute(AttributeName::Subtype).value(), participant);
436 PassingControlLinePtr control_line = buildControlLine(sub_bound, change_type, participant);
437 area.addRegulatoryElement(control_line);
438 map->add(control_line);
439
440 i++;
441 }
442}
PassingControlLinePtr buildControlLine(LineString3d &bound, const LaneChangeType type, const std::string &participant)
Helper function constructs a PassingControlLine based off the provided bound and lane change type.
LaneChangeType getChangeType(const std::string &type, const std::string &subtype, const std::string &participant)
Helper function to determine the type of lane change implicitly allowed by the markings on the road.

References buildControlLine(), getChangeType(), and process_bag::i.

Referenced by lanelet::MapConformer::ensureCompliance().

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

◆ addInferredPassingControlLine() [2/2]

void lanelet::MapConformer::anonymous_namespace{MapConformer.cpp}::addInferredPassingControlLine ( Lanelet &  lanelet,
lanelet::LaneletMapPtr  map 
)

Generate PassingControlLines from the inferred regulations in the provided map and lanelet.

Parameters
laneletThe lanelet to generate control lines for
mapThe map which the lanelet is part of

Definition at line 310 of file MapConformer.cpp.

311{
312 // Since this class is only designed to add passing control lines based on lane changes
313 // we will always assume the participant is a vehicle
314 std::string participant(lanelet::Participants::Vehicle);
315
316 LineString3d left_bound = lanelet.leftBound();
317 LineString3d right_bound = lanelet.rightBound();
318
319 // Determine possibility of lane change for left and right bounds
320 LaneChangeType left_type = getChangeType(left_bound.attribute(AttributeName::Type).value(),
321 left_bound.attribute(AttributeName::Subtype).value(), participant);
322 LaneChangeType right_type = getChangeType(right_bound.attribute(AttributeName::Type).value(),
323 right_bound.attribute(AttributeName::Subtype).value(), participant);
324
325 auto local_control_lines = lanelet.regulatoryElementsAs<PassingControlLine>();
326
327 bool foundLeft = false;
328 bool foundRight = false;
329
330 // Iterate over all regulatory elements in the map to determine if there is an existing regulation for this
331 // lanelet's bounds
332 for (auto reg_elem : map->regulatoryElementLayer)
333 {
334 if (reg_elem->attribute(AttributeName::Subtype).value() != PassingControlLine::RuleName)
335 {
336 continue;
337 }
338
339 auto pcl = std::static_pointer_cast<PassingControlLine>(reg_elem);
340 for (auto sub_line : pcl->controlLine())
341 {
342 bool shouldAdd = false;
343
344 if (left_bound.id() == sub_line.id() && !foundLeft)
345 {
346 foundLeft = true;
347 shouldAdd = !lanelet::utils::contains(local_control_lines, pcl);
348 }
349 else if (right_bound.id() == sub_line.id() && !foundRight)
350 {
351 foundRight = true;
352 shouldAdd = !lanelet::utils::contains(local_control_lines, pcl);
353 }
354 // Check if our lanelet contains this control line
355 // If it does not then add it
356 if (shouldAdd)
357 {
358 lanelet.addRegulatoryElement(pcl);
359 }
360 }
361
362 }
363
364 // If no existing regulation was found for this lanelet's right or left bound then create a new one and add it to
365 // the lanelet and the map
366 if (!foundLeft)
367 {
368 PassingControlLinePtr pcl_left = buildControlLine(left_bound, left_type, participant);
369 lanelet.addRegulatoryElement(pcl_left);
370 map->add(pcl_left);
371 }
372 if (!foundRight)
373 {
374 PassingControlLinePtr pcl_right = buildControlLine(right_bound, right_type, participant);
375 lanelet.addRegulatoryElement(pcl_right);
376 map->add(pcl_right);
377 }
378}

References buildControlLine(), and getChangeType().

Here is the call graph for this function:

◆ addValidSpeedLimit()

void lanelet::MapConformer::anonymous_namespace{MapConformer.cpp}::addValidSpeedLimit ( Lanelet &  lanelet,
lanelet::LaneletMapPtr  map,
lanelet::Velocity  config_limit,
const std::vector< lanelet::traffic_rules::TrafficRulesUPtr > &  default_traffic_rules 
)

Definition at line 481 of file MapConformer.cpp.

483{
484 lanelet::Velocity max_speed;
485 auto speed_limit = lanelet.regulatoryElementsAs<DigitalSpeedLimit>();
486 if(config_limit < 80_mph && config_limit > 0_mph)//Accounting for the configured speed limit, input zero when not in use
487 {
488 max_speed = config_limit;
489 }
490 else
491 {
492 max_speed = 80_mph;
493 }
494
495 // If the lanelet does not have a digital speed limit then add one with the maximum value of 80
496 std::vector<std::string> allowed_participants;
497 //Maximum speed limit is 80
498
499
500 if (speed_limit.empty())//If there is no assigned speed limit value
501 {
502
503 for(const auto& rules : default_traffic_rules)
504 {
505 if (rules->canPass(lanelet))
506 {
507 allowed_participants.emplace_back(rules->participant());
508 }
509 }
510 if (!allowed_participants.empty())
511 {
512
513 auto rar = std::make_shared<DigitalSpeedLimit>(DigitalSpeedLimit::buildData(lanelet::utils::getId(), max_speed, {lanelet},
514 {}, allowed_participants));
515
516 lanelet.addRegulatoryElement(rar);
517 map->add(rar);//Add DigitalSpeedLimit data to the map
518
519 }
520 }
521 else //If the speed limit value already exists
522 {
523 for(const auto& rules : default_traffic_rules)
524 {
525 if (rules->canPass(lanelet))
526 {
527 allowed_participants.emplace_back(rules->participant());
528 }
529 }
530 if(speed_limit.back().get()->speed_limit_ > max_speed)//Check that speed limit value does not exceed the maximum value
531 {
532
533 RCLCPP_DEBUG_STREAM( rclcpp::get_logger("lanelet::MapConformer"), "Invalid speed limit value. Value reset to maximum speed limit.");
534 auto rar = std::make_shared<DigitalSpeedLimit>(DigitalSpeedLimit::buildData(lanelet::utils::getId(), max_speed, {lanelet},
535 {}, allowed_participants));
536 lanelet.removeRegulatoryElement(speed_limit.back());
537 lanelet.addRegulatoryElement(rar);
538 map->update(lanelet, rar);//Add DigitalSpeedLimit data to the map
539 RCLCPP_INFO_STREAM( rclcpp::get_logger("lanelet::MapConformer"), "Number of Regulatory Elements: "<< map->regulatoryElementLayer.size());
540
541
542 }
543
544 }
545}

Referenced by lanelet::MapConformer::ensureCompliance().

Here is the caller graph for this function:

◆ buildControlLine()

PassingControlLinePtr lanelet::MapConformer::anonymous_namespace{MapConformer.cpp}::buildControlLine ( LineString3d &  bound,
const LaneChangeType  type,
const std::string &  participant 
)

Helper function constructs a PassingControlLine based off the provided bound and lane change type.

Parameters
boundThe bound which will mark the control line
typeThe type of lane change permitted by this bound's implied regulations
participantThe participant that is allowed to cross this control line
Returns
A new PasssingControlLine which was created based off the bound

Definition at line 198 of file MapConformer.cpp.

199{
200 if (bound.inverted())
201 {
202 switch (type)
203 {
204 case LaneChangeType::ToRight:
205 return std::shared_ptr<PassingControlLine>(new PassingControlLine(
206 PassingControlLine::buildData(lanelet::utils::getId(), { bound.invert() }, {}, { participant })));
207 case LaneChangeType::ToLeft:
208 return std::shared_ptr<PassingControlLine>(new PassingControlLine(
209 PassingControlLine::buildData(lanelet::utils::getId(), { bound.invert() }, { participant }, {})));
210 case LaneChangeType::Both:
211 return std::shared_ptr<PassingControlLine>(new PassingControlLine(PassingControlLine::buildData(
212 lanelet::utils::getId(), { bound.invert() }, { participant }, { participant })));
213 default: // LaneChangeType::None
214 return std::shared_ptr<PassingControlLine>(
215 new PassingControlLine(PassingControlLine::buildData(lanelet::utils::getId(), { bound.invert() }, {}, {})));
216 }
217 }
218 else
219 {
220 switch (type)
221 {
222 case LaneChangeType::ToRight:
223 return std::shared_ptr<PassingControlLine>(new PassingControlLine(
224 PassingControlLine::buildData(lanelet::utils::getId(), { bound }, { participant }, {})));
225 case LaneChangeType::ToLeft:
226 return std::shared_ptr<PassingControlLine>(new PassingControlLine(
227 PassingControlLine::buildData(lanelet::utils::getId(), { bound }, {}, { participant })));
228 case LaneChangeType::Both:
229 return std::shared_ptr<PassingControlLine>(new PassingControlLine(
230 PassingControlLine::buildData(lanelet::utils::getId(), { bound }, { participant }, { participant })));
231 default: // LaneChangeType::None
232 return std::shared_ptr<PassingControlLine>(
233 new PassingControlLine(PassingControlLine::buildData(lanelet::utils::getId(), { bound }, {}, {})));
234 }
235 }
236}

Referenced by addInferredPassingControlLine().

Here is the caller graph for this function:

◆ getAllGermanTrafficRules()

std::vector< lanelet::traffic_rules::TrafficRulesUPtr > lanelet::MapConformer::anonymous_namespace{MapConformer.cpp}::getAllGermanTrafficRules ( )

Helper function to return the set of all german traffic rules which are currently implemented.

Returns
A list of german traffic rules which have been implemented

Definition at line 66 of file MapConformer.cpp.

67{
68 std::vector<lanelet::traffic_rules::TrafficRulesUPtr> german_traffic_rules_set;
69 german_traffic_rules_set.reserve(PARTICIPANT_COUNT);
70
71 for (size_t i = 0; i < PARTICIPANT_COUNT; i++)
72 {
73 // This loop is designed to identify the set of currently supported participants for german traffic rules
74 // Using exceptions as logic like this is not usually a good practice, but since this is an operation performed only
75 // at startup on a small number of elements efficiency should not be an issue
76 try
77 {
78 lanelet::traffic_rules::TrafficRulesUPtr traffic_rules =
79 lanelet::traffic_rules::TrafficRulesFactory::create(lanelet::Locations::Germany, participant_types[i]);
80 german_traffic_rules_set.emplace_back(std::move(traffic_rules));
81 }
82 catch (const lanelet::InvalidInputError& e)
83 {
84 // Ignore participants which there is no generic rules for
85 RCLCPP_INFO_STREAM ( rclcpp::get_logger("MapConformer"), "Ignoring participant: " << participant_types[i] << ", which there is no generic rule for...");
86 }
87 }
88
89 return german_traffic_rules_set;
90}
constexpr const char * participant_types[PARTICIPANT_COUNT]

References process_bag::i, PARTICIPANT_COUNT, and participant_types.

Referenced by lanelet::MapConformer::ensureCompliance().

Here is the caller graph for this function:

◆ getChangeType()

LaneChangeType lanelet::MapConformer::anonymous_namespace{MapConformer.cpp}::getChangeType ( const std::string &  type,
const std::string &  subtype,
const std::string &  participant 
)

Helper function to determine the type of lane change implicitly allowed by the markings on the road.

This function has been copied from lanelet2_traffic_rules/src/GenericTrafficRules.cpp as it was not exposed by the Lanelet2 libraray. The function therefore has the same functionality as the GenericTrafficRules class

https://github.com/fzi-forschungszentrum-informatik/Lanelet2/blob/master/lanelet2_traffic_rules/src/GenericTrafficRules.cpp The source function is copyrighted under BSD 3-Clause "New" or "Revised" License a copy of that notice has been included with this package

Parameters
typeThe type of the line string marking
subtypeThe sub-type of the line string marking
participantThe type of participant the rules apply too
Returns
An enum describing the type of lane change allowed by the road markings

Definition at line 155 of file MapConformer.cpp.

156{
157 using LaneChangeMap = std::map<std::pair<std::string, std::string>, LaneChangeType>;
158 const static LaneChangeMap VehicleChangeType{
159 { { AttributeValueString::LineThin, AttributeValueString::Dashed }, LaneChangeType::Both },
160 { { AttributeValueString::LineThick, AttributeValueString::Dashed }, LaneChangeType::Both },
161 { { AttributeValueString::LineThin, AttributeValueString::DashedSolid }, LaneChangeType::ToRight },
162 { { AttributeValueString::LineThick, AttributeValueString::DashedSolid }, LaneChangeType::ToRight },
163 { { AttributeValueString::LineThin, AttributeValueString::SolidDashed }, LaneChangeType::ToLeft },
164 { { AttributeValueString::LineThick, AttributeValueString::SolidDashed }, LaneChangeType::ToLeft }
165 };
166 const static LaneChangeMap PedestrianChangeType{ { { AttributeValueString::Curbstone, AttributeValueString::Low },
167 LaneChangeType::Both } };
168
169 if (startswith(participant, Participants::Vehicle))
170 {
171 return getMapOrDefault(VehicleChangeType, std::make_pair(type, subtype), LaneChangeType::None);
172 }
173 if (participant == Participants::Pedestrian)
174 {
175 return getMapOrDefault(PedestrianChangeType, std::make_pair(type, subtype), LaneChangeType::None);
176 }
177 if (participant == Participants::Bicycle)
178 {
179 auto asVehicle = getMapOrDefault(VehicleChangeType, std::make_pair(type, subtype), LaneChangeType::None);
180 if (asVehicle != LaneChangeType::None)
181 {
182 return asVehicle;
183 }
184 return getMapOrDefault(PedestrianChangeType, std::make_pair(type, subtype), LaneChangeType::None);
185 }
186 return LaneChangeType::None;
187}
bool startswith(const std::string &str, const std::string &substr)
Helper function to check if a string starts with another string.
Value getMapOrDefault(const Map &map, Key key, Value defaultVal)
Helper function to get a value from a map or return a default value when key is not present.

References getMapOrDefault(), and startswith().

Referenced by addInferredPassingControlLine().

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

◆ getMapOrDefault()

template<typename Map , typename Key , typename Value >
Value lanelet::MapConformer::anonymous_namespace{MapConformer.cpp}::getMapOrDefault ( const Map &  map,
Key  key,
Value  defaultVal 
)

Helper function to get a value from a map or return a default value when key is not present.

This function has been copied from lanelet2_traffic_rules/src/GenericTrafficRules.cpp as it was not exposed by the Lanelet2 libraray. The function therefore has the same functionality as the GenericTrafficRules class

https://github.com/fzi-forschungszentrum-informatik/Lanelet2/blob/master/lanelet2_traffic_rules/src/GenericTrafficRules.cpp The source function is copyrighted under BSD 3-Clause "New" or "Revised" License a copy of that notice has been included with this package

Parameters
mapThe map to search
keyThe key to evaluate
defaultValThe default to return if key is not in map
Returns
Value at key in map or defaultVal if key is not in map

Definition at line 109 of file MapConformer.cpp.

110{
111 auto elem = map.find(key);
112 if (elem == map.end())
113 {
114 return defaultVal;
115 }
116 return elem->second;
117}

Referenced by getChangeType().

Here is the caller graph for this function:

◆ startswith()

bool lanelet::MapConformer::anonymous_namespace{MapConformer.cpp}::startswith ( const std::string &  str,
const std::string &  substr 
)

Helper function to check if a string starts with another string.

This function has been copied from lanelet2_traffic_rules/src/GenericTrafficRules.cpp as it was not exposed by the Lanelet2 libraray. The function therefore has the same functionality as the GenericTrafficRules class

https://github.com/fzi-forschungszentrum-informatik/Lanelet2/blob/master/lanelet2_traffic_rules/src/GenericTrafficRules.cpp The source function is copyrighted under BSD 3-Clause "New" or "Revised" License a copy of that notice has been included with this package

Parameters
strBase string
substrStarting string to check for
Returns
True if str starts with substr

Definition at line 134 of file MapConformer.cpp.

135{
136 return str.compare(0, substr.size(), substr) == 0;
137}

Referenced by getChangeType().

Here is the caller graph for this function:

Variable Documentation

◆ PARTICIPANT_COUNT

constexpr size_t lanelet::MapConformer::anonymous_namespace{MapConformer.cpp}::PARTICIPANT_COUNT = 12
constexpr

Definition at line 47 of file MapConformer.cpp.

Referenced by getAllGermanTrafficRules().

◆ participant_types

constexpr const char* lanelet::MapConformer::anonymous_namespace{MapConformer.cpp}::participant_types[PARTICIPANT_COUNT]
constexpr
Initial value:
= { lanelet::Participants::Vehicle,
lanelet::Participants::VehicleBus,
lanelet::Participants::VehicleCar,
lanelet::Participants::VehicleCarElectric,
lanelet::Participants::VehicleCarCombustion,
lanelet::Participants::VehicleTruck,
lanelet::Participants::VehicleMotorcycle,
lanelet::Participants::VehicleTaxi,
lanelet::Participants::VehicleEmergency,
lanelet::Participants::Pedestrian,
lanelet::Participants::Bicycle,
lanelet::Participants::Train }

Definition at line 48 of file MapConformer.cpp.

Referenced by getAllGermanTrafficRules().