GermanTrafficRules.cpp
Go to the documentation of this file.
2 
6 
9 
10 using namespace std::string_literals;
11 
12 namespace lanelet {
13 namespace traffic_rules {
14 
15 namespace {
16 RegisterTrafficRules<GermanVehicle> gvRules(Locations::Germany, Participants::Vehicle);
17 RegisterTrafficRules<GermanPedestrian> gpRules(Locations::Germany, Participants::Pedestrian);
18 RegisterTrafficRules<GermanBicycle> gbRules(Locations::Germany, Participants::Bicycle);
19 
20 Velocity trafficSignToVelocity(const std::string& typeString) {
21  using namespace lanelet::units::literals;
22  const static std::map<std::string, Velocity> StrToVelocity{
23  {"de274", 30_kmh}, {"de274-5", 5_kmh}, {"de274-10", 10_kmh}, {"de274-15", 15_kmh},
24  {"de274-20", 20_kmh}, {"de274-30", 30_kmh}, {"de274-40", 40_kmh}, {"de274-50", 50_kmh},
25  {"de274-60", 60_kmh}, {"de274-70", 70_kmh}, {"de274-80", 80_kmh}, {"de274-90", 90_kmh},
26  {"de274-100", 100_kmh}, {"de274-110", 110_kmh}, {"de274-120", 120_kmh}, {"de274-130", 130_kmh},
27  {"de274_1", 30_kmh}, {"de274_1-20", 20_kmh}, {"de310", 50_kmh}};
28  try {
29  return StrToVelocity.at(typeString);
30  } catch (std::out_of_range&) {
31  // try to interpret typeString directly as velocity
32  Attribute asAttribute(typeString);
33  auto velocity = asAttribute.asVelocity();
34  if (!!velocity) {
35  return *velocity;
36  }
37  throw lanelet::InterpretationError("Unable to interpret the velocity information from " + typeString);
38  }
39 }
40 } // namespace
41 
42 Optional<SpeedLimitInformation> GermanVehicle::speedLimit(const RegulatoryElementConstPtrs& regelems) const {
43  for (const auto& regelem : regelems) {
44  auto speedLimit = std::dynamic_pointer_cast<const SpeedLimit>(regelem);
45  if (!!speedLimit) {
46  return SpeedLimitInformation{trafficSignToVelocity(speedLimit->type()), true};
47  }
48  }
49  return {};
50 }
51 
53  using namespace units::literals;
54  return {{50_kmh}, {100_kmh}, {130_kmh, false}, {130_kmh, false}, {7_kmh}, {5_kmh}, {20_kmh}};
55 }
56 
57 } // namespace traffic_rules
58 } // namespace lanelet
GermanTrafficRules.h
Velocity
units::MPSQuantity Velocity
lanelet
lanelet::traffic_rules::CountrySpeedLimits
Definition: GenericTrafficRules.h:11
TrafficRulesFactory.h
lanelet::traffic_rules::germanSpeedLimits
CountrySpeedLimits germanSpeedLimits()
Definition: GermanTrafficRules.cpp:52
Forward.h
BasicRegulatoryElements.h
Units.h
lanelet::Optional
boost::optional< T > Optional
lanelet::InterpretationError
Definition: Exceptions.h:7
lanelet::traffic_rules::SpeedLimitInformation
Definition: TrafficRules.h:8
lanelet::RegulatoryElementConstPtrs
std::vector< RegulatoryElementConstPtr > RegulatoryElementConstPtrs
lanelet::units::literals
Exceptions.h


lanelet2_traffic_rules
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:26:07