scenario_simulator_v2 C++ API
traffic_rules.hpp
Go to the documentation of this file.
1 // Copyright 2015 TIER IV, Inc. All rights reserved.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef TRAFFIC_SIMULATOR__HDMAP_UTILS__TRAFFIC_RULES_HPP_
16 #define TRAFFIC_SIMULATOR__HDMAP_UTILS__TRAFFIC_RULES_HPP_
17 
18 #include <lanelet2_traffic_rules/GermanTrafficRules.h>
19 
20 namespace traffic_simulator
21 {
22 namespace lanelet_wrapper
23 {
24 struct Locations
25 {
28  static constexpr char RoadShoulderPassableGermany[] = "de_road_shoulder_passable";
29 };
30 
31 class GermanRoadShoulderPassableVehicle : public lanelet::traffic_rules::GermanVehicle
32 {
33 public:
34  using lanelet::traffic_rules::GenericTrafficRules::canPass;
35  using lanelet::traffic_rules::GermanVehicle::GermanVehicle;
36 
37 protected:
39  auto canPass(const std::string & type, const std::string & /*location*/) const
40  -> lanelet::Optional<bool> override
41  {
42  using lanelet::AttributeValueString;
43  using lanelet::Participants;
44  const static std::map<std::string, std::vector<std::string>, std::less<>> participants_map{
45  // clang-format off
46  {"", {Participants::Vehicle}},
47  {AttributeValueString::Road, {Participants::Vehicle, Participants::Bicycle}},
48  {"road_shoulder", {Participants::Vehicle, Participants::Bicycle}}, // add road_shoulder
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}}
58  // clang-format on
59  };
60  auto participants = participants_map.find(type);
61  if (participants == participants_map.end()) {
62  return {};
63  }
64 
65  auto startsWith = [](std::string_view str, std::string_view substr) {
66  return str.compare(0, substr.size(), substr) == 0;
67  };
68  return lanelet::utils::anyOf(participants->second, [this, startsWith](auto & participant) {
69  return startsWith(this->participant(), participant);
70  });
71  }
72 
73  lanelet::traffic_rules::LaneChangeType laneChangeType(
74  const lanelet::ConstLineString3d &, bool) const override;
75 };
76 } // namespace lanelet_wrapper
77 } // namespace traffic_simulator
78 #endif // TRAFFIC_SIMULATOR__HDMAP_UTILS__TRAFFIC_RULES_HPP_
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
Definition: api.hpp:48
std::string string
Definition: junit5.hpp:26
Definition: traffic_rules.hpp:25
static constexpr char RoadShoulderPassableGermany[]
Definition: traffic_rules.hpp:28