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 hdmap_utils
21 {
22 struct Locations
23 {
26  static constexpr char RoadShoulderPassableGermany[] = "de_road_shoulder_passable";
27 };
28 
29 class GermanRoadShoulderPassableVehicle : public lanelet::traffic_rules::GermanVehicle
30 {
31 public:
32  using lanelet::traffic_rules::GermanVehicle::GermanVehicle;
33 
34 protected:
36  lanelet::Optional<bool> canPass(
37  const std::string & type, const std::string & /*location*/) const override
38  {
39  using lanelet::AttributeValueString;
40  using lanelet::Participants;
41  const static std::map<std::string, std::vector<std::string>> participants_map{
42  // clang-format off
43  {"", {Participants::Vehicle}},
44  {AttributeValueString::Road, {Participants::Vehicle, Participants::Bicycle}},
45  {"road_shoulder", {Participants::Vehicle, Participants::Bicycle}}, // add road_shoulder
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}}
55  // clang-format on
56  };
57  auto participants = participants_map.find(type);
58  if (participants == participants_map.end()) {
59  return {};
60  }
61 
62  auto startsWith = [](const std::string & str, const std::string & substr) {
63  return str.compare(0, substr.size(), substr) == 0;
64  };
65  return lanelet::utils::anyOf(participants->second, [this, startsWith](auto & participant) {
66  return startsWith(this->participant(), participant);
67  });
68  }
69 
70  lanelet::traffic_rules::LaneChangeType laneChangeType(
71  const lanelet::ConstLineString3d &, bool) const override;
72 };
73 } // namespace hdmap_utils
74 #endif // TRAFFIC_SIMULATOR__HDMAP_UTILS__TRAFFIC_RULES_HPP_
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
Definition: cache.hpp:46
std::string string
Definition: junit5.hpp:26
Definition: traffic_rules.hpp:23
static constexpr char RoadShoulderPassableGermany[]
Definition: traffic_rules.hpp:26