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>
22 namespace lanelet_wrapper
34 using lanelet::traffic_rules::GenericTrafficRules::canPass;
35 using lanelet::traffic_rules::GermanVehicle::GermanVehicle;
40 -> lanelet::Optional<bool>
override
42 using lanelet::AttributeValueString;
43 using lanelet::Participants;
44 const static std::map<std::string, std::vector<std::string>, std::less<>> participants_map{
46 {
"", {Participants::Vehicle}},
47 {AttributeValueString::Road, {Participants::Vehicle, Participants::Bicycle}},
48 {
"road_shoulder", {Participants::Vehicle, Participants::Bicycle}},
49 {AttributeValueString::Highway, {Participants::Vehicle}},
50 {AttributeValueString::BicycleLane, {Participants::Bicycle}},
51 {AttributeValueString::PlayStreet, {Participants::Pedestrian, Participants::Bicycle, Participants::Vehicle}},
52 {AttributeValueString::EmergencyLane, {Participants::VehicleEmergency}},
53 {AttributeValueString::Exit, {Participants::Pedestrian, Participants::Bicycle, Participants::Vehicle}},
54 {AttributeValueString::Walkway, {Participants::Pedestrian}},
55 {AttributeValueString::Crosswalk, {Participants::Pedestrian}},
56 {AttributeValueString::Stairs, {Participants::Pedestrian}},
57 {AttributeValueString::SharedWalkway, {Participants::Pedestrian, Participants::Bicycle}}
60 auto participants = participants_map.find(type);
61 if (participants == participants_map.end()) {
65 auto startsWith = [](std::string_view str, std::string_view substr) {
66 return str.compare(0, substr.size(), substr) == 0;
68 return lanelet::utils::anyOf(participants->second, [
this, startsWith](
auto & participant) {
69 return startsWith(this->participant(), participant);
74 const lanelet::ConstLineString3d &,
bool)
const override;
Definition: traffic_rules.hpp:32
lanelet::traffic_rules::LaneChangeType laneChangeType(const lanelet::ConstLineString3d &, bool) const override
Definition: traffic_rules.cpp:27
auto canPass(const std::string &type, const std::string &) const -> lanelet::Optional< bool > override
Definition: traffic_rules.hpp:39
std::string string
Definition: junit5.hpp:26
Definition: traffic_rules.hpp:25
static constexpr char RoadShoulderPassableGermany[]
Definition: traffic_rules.hpp:28