15 #ifndef TRAFFIC_SIMULATOR__HDMAP_UTILS__TRAFFIC_RULES_HPP_
16 #define TRAFFIC_SIMULATOR__HDMAP_UTILS__TRAFFIC_RULES_HPP_
18 #include <lanelet2_traffic_rules/GermanTrafficRules.h>
32 using lanelet::traffic_rules::GermanVehicle::GermanVehicle;
39 using lanelet::AttributeValueString;
40 using lanelet::Participants;
41 const static std::map<std::string, std::vector<std::string>> participants_map{
43 {
"", {Participants::Vehicle}},
44 {AttributeValueString::Road, {Participants::Vehicle, Participants::Bicycle}},
45 {
"road_shoulder", {Participants::Vehicle, Participants::Bicycle}},
46 {AttributeValueString::Highway, {Participants::Vehicle}},
47 {AttributeValueString::BicycleLane, {Participants::Bicycle}},
48 {AttributeValueString::PlayStreet, {Participants::Pedestrian, Participants::Bicycle, Participants::Vehicle}},
49 {AttributeValueString::EmergencyLane, {Participants::VehicleEmergency}},
50 {AttributeValueString::Exit, {Participants::Pedestrian, Participants::Bicycle, Participants::Vehicle}},
51 {AttributeValueString::Walkway, {Participants::Pedestrian}},
52 {AttributeValueString::Crosswalk, {Participants::Pedestrian}},
53 {AttributeValueString::Stairs, {Participants::Pedestrian}},
54 {AttributeValueString::SharedWalkway, {Participants::Pedestrian, Participants::Bicycle}}
57 auto participants = participants_map.find(type);
58 if (participants == participants_map.end()) {
63 return str.compare(0, substr.size(), substr) == 0;
65 return lanelet::utils::anyOf(participants->second, [
this, startsWith](
auto & participant) {
66 return startsWith(this->participant(), participant);
71 const lanelet::ConstLineString3d &,
bool)
const override;
Definition: traffic_rules.hpp:30
lanelet::traffic_rules::LaneChangeType laneChangeType(const lanelet::ConstLineString3d &, bool) const override
Definition: traffic_rules.cpp:24
lanelet::Optional< bool > canPass(const std::string &type, const std::string &) const override
Definition: traffic_rules.hpp:36
std::string string
Definition: junit5.hpp:26
Definition: traffic_rules.hpp:23
static constexpr char RoadShoulderPassableGermany[]
Definition: traffic_rules.hpp:26