scenario_simulator_v2 C++ API
lanelet_wrapper.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__LANELET_WRAPPER_HPP_
16 #define TRAFFIC_SIMULATOR__LANELET_WRAPPER_HPP_
17 
18 #include <lanelet2_core/geometry/Lanelet.h>
19 #include <lanelet2_core/primitives/BasicRegulatoryElements.h>
20 #include <lanelet2_core/primitives/LaneletSequence.h>
21 #include <lanelet2_routing/RoutingGraph.h>
22 #include <lanelet2_routing/RoutingGraphContainer.h>
23 #include <lanelet2_traffic_rules/TrafficRulesFactory.h>
24 
25 #include <autoware_lanelet2_extension/utility/utilities.hpp>
26 #include <filesystem>
30 #include <geometry_msgs/msg/point.hpp>
31 #include <geometry_msgs/msg/pose.hpp>
32 #include <geometry_msgs/msg/pose_stamped.hpp>
33 #include <geometry_msgs/msg/vector3.hpp>
34 #include <mutex>
38 #include <traffic_simulator_msgs/msg/bounding_box.hpp>
39 #include <traffic_simulator_msgs/msg/entity_type.hpp>
40 #include <traffic_simulator_msgs/msg/lanelet_pose.hpp>
41 
42 namespace std
43 {
44 template <>
45 struct hash<std::tuple<lanelet::Id, lanelet::Id, bool>>
46 {
47 public:
48  size_t operator()(const std::tuple<lanelet::Id, lanelet::Id, bool> & data) const
49  {
50  std::hash<lanelet::Id> lanelet_id_hash;
51  size_t seed = 0;
53  seed ^= lanelet_id_hash(std::get<0>(data)) + 0x9e3779b9 + (seed << 6) + (seed >> 2);
54  seed ^= lanelet_id_hash(std::get<1>(data)) + 0x9e3779b9 + (seed << 6) + (seed >> 2);
55  seed ^= std::hash<bool>{}(std::get<2>(data)) + 0x9e3779b9 + (seed << 6) + (seed >> 2);
56  return seed;
57  }
58 };
59 } // namespace std
60 
61 namespace traffic_simulator
62 {
63 namespace lanelet_wrapper
64 {
76 
78 {
79 public:
80  auto getRoute(
81  const lanelet::Id from_lanelet_id, const lanelet::Id to_lanelet_id,
82  const lanelet::LaneletMapPtr & lanelet_map, const RoutingConfiguration & routing_configuration,
83  const lanelet::routing::RoutingGraphConstPtr & routing_graph) -> lanelet::Ids
84  {
85  if (!exists(from_lanelet_id, to_lanelet_id, routing_configuration.allow_lane_change)) {
87  constexpr int routing_cost_id = 0;
88  const auto & from_lanelet = lanelet_map->laneletLayer.get(from_lanelet_id);
89  const auto & to_lanelet = lanelet_map->laneletLayer.get(to_lanelet_id);
90  if (const auto route = routing_graph->getRoute(
91  from_lanelet, to_lanelet, routing_cost_id, routing_configuration.allow_lane_change);
92  !route || route->shortestPath().empty()) {
93  appendData(
94  from_lanelet_id, to_lanelet_id, routing_configuration.allow_lane_change, lanelet::Ids());
95  } else {
96  lanelet::Ids shortest_path_ids;
97  for (const auto & lanelet : route->shortestPath()) {
98  shortest_path_ids.push_back(lanelet.id());
99  }
100  appendData(
101  from_lanelet_id, to_lanelet_id, routing_configuration.allow_lane_change,
102  shortest_path_ids);
103  }
104  }
105  return readData(from_lanelet_id, to_lanelet_id, routing_configuration.allow_lane_change);
106  }
107 
108  auto getRoute(const lanelet::Id from, const lanelet::Id to, const bool allow_lane_change)
109  -> decltype(auto)
110  {
111  if (!exists(from, to, allow_lane_change)) {
113  "route from : ", from, " to : ", to, (allow_lane_change ? " with" : " without"),
114  " lane change does not exists on route cache.");
115  } else {
116  return readData(from, to, allow_lane_change);
117  }
118  }
119 
120 private:
121  auto exists(const lanelet::Id from, const lanelet::Id to, const bool allow_lane_change) -> bool
122  {
123  std::lock_guard lock(mutex_);
124  std::tuple<lanelet::Id, lanelet::Id, bool> key = {from, to, allow_lane_change};
125  return data_.find(key) != data_.end();
126  }
127 
128  auto readData(const lanelet::Id from, const lanelet::Id to, const bool allow_lane_change)
129  -> lanelet::Ids
130  {
131  std::lock_guard lock(mutex_);
132  return data_.at({from, to, allow_lane_change});
133  }
134 
135  auto appendData(
136  const lanelet::Id from, const lanelet::Id to, const bool allow_lane_change,
137  const lanelet::Ids & route) -> void
138  {
139  std::lock_guard lock(mutex_);
140  data_[{from, to, allow_lane_change}] = route;
141  }
142 
143  std::unordered_map<std::tuple<lanelet::Id, lanelet::Id, bool>, lanelet::Ids> data_;
144  std::mutex mutex_;
145 };
146 
148 {
149 public:
150  auto getCenterPoints(const lanelet::Id lanelet_id, const lanelet::LaneletMapPtr & lanelet_map)
151  -> decltype(auto)
152  {
153  if (!exists(lanelet_id)) {
154  appendData(lanelet_id, centerPoints(lanelet_id, lanelet_map));
155  }
156  return readData(lanelet_id);
157  }
158 
160  const lanelet::Id lanelet_id, const lanelet::LaneletMapPtr & lanelet_map) -> decltype(auto)
161  {
162  if (!exists(lanelet_id)) {
163  appendData(lanelet_id, centerPoints(lanelet_id, lanelet_map));
164  }
165  return readDataSpline(lanelet_id);
166  }
167 
168 private:
169  auto exists(const lanelet::Id lanelet_id) -> bool
170  {
171  std::lock_guard lock(mutex_);
172  return data_.find(lanelet_id) != data_.end();
173  }
174 
175  auto readData(const lanelet::Id lanelet_id) -> const std::vector<Point> &
176  {
177  std::lock_guard lock(mutex_);
178  return data_.at(lanelet_id);
179  }
180 
181  auto readDataSpline(const lanelet::Id lanelet_id) -> std::shared_ptr<Spline>
182  {
183  std::lock_guard lock(mutex_);
184  return splines_.at(lanelet_id);
185  }
186 
187  auto appendData(const lanelet::Id lanelet_id, const std::vector<Point> & route) -> void
188  {
189  std::lock_guard lock(mutex_);
190  data_[lanelet_id] = route;
191  splines_[lanelet_id] = std::make_shared<Spline>(route);
192  }
193 
194  auto centerPoints(const lanelet::Id lanelet_id, const lanelet::LaneletMapPtr & lanelet_map) const
195  -> std::vector<Point>
196  {
197  std::vector<Point> center_points;
198  for (const auto & point : lanelet_map->laneletLayer.get(lanelet_id).centerline()) {
199  center_points.push_back(geometry_msgs::build<Point>().x(point.x()).y(point.y()).z(point.z()));
200  }
201  if (center_points.size() == 2) {
202  const auto p0 = center_points[0];
203  const auto p2 = center_points[1];
204  const auto p1 = geometry_msgs::build<Point>()
205  .x((p0.x + p2.x) * 0.5)
206  .y((p0.y + p2.y) * 0.5)
207  .z((p0.z + p2.z) * 0.5);
208  center_points.clear();
209  center_points.push_back(p0);
210  center_points.push_back(p1);
211  center_points.push_back(p2);
212  }
213  return center_points;
214  }
215 
216  std::unordered_map<lanelet::Id, std::vector<Point>> data_;
217  std::unordered_map<lanelet::Id, std::shared_ptr<Spline>> splines_;
218  std::mutex mutex_;
219 };
220 
222 {
223 public:
224  auto getLength(lanelet::Id lanelet_id) -> double
225  {
226  if (!exists(lanelet_id)) {
227  THROW_SIMULATION_ERROR("length of : ", lanelet_id, " does not exists on route cache.");
228  }
229  return readData(lanelet_id);
230  }
231 
232  auto getLength(const lanelet::Id lanelet_id, const lanelet::LaneletMapPtr & lanelet_map) -> double
233  {
234  if (!exists(lanelet_id)) {
235  appendData(
236  lanelet_id, lanelet::utils::getLaneletLength2d(lanelet_map->laneletLayer.get(lanelet_id)));
237  }
238  return readData(lanelet_id);
239  }
240 
241 private:
242  auto exists(const lanelet::Id lanelet_id) -> bool
243  {
244  std::lock_guard lock(mutex_);
245  return data_.find(lanelet_id) != data_.end();
246  }
247 
248  auto readData(const lanelet::Id lanelet_id) -> double
249  {
250  std::lock_guard lock(mutex_);
251  return data_.at(lanelet_id);
252  }
253 
254  auto appendData(const lanelet::Id lanelet_id, double length) -> void
255  {
256  std::lock_guard lock(mutex_);
257  data_[lanelet_id] = length;
258  }
259 
260  std::unordered_map<lanelet::Id, double> data_;
261  std::mutex mutex_;
262 };
263 
265 {
266  lanelet::traffic_rules::TrafficRulesPtr rules;
267  lanelet::routing::RoutingGraphConstPtr graph;
269 
271  const lanelet::LaneletMapPtr lanelet_map_ptr, const std::string & locations,
272  const std::string & participants)
273  {
274  rules = lanelet::traffic_rules::TrafficRulesFactory::create(locations, participants);
275  graph = lanelet::routing::RoutingGraph::build(*lanelet_map_ptr, *rules);
276  }
277 };
278 
280 {
281 public:
282  static auto activate(const std::string & lanelet_map_path) -> void;
283 
284  [[nodiscard]] static auto map() -> lanelet::LaneletMapPtr;
285  [[nodiscard]] static auto routingGraph(const RoutingGraphType type)
286  -> lanelet::routing::RoutingGraphConstPtr;
287  [[nodiscard]] static auto trafficRules(const RoutingGraphType type)
288  -> lanelet::traffic_rules::TrafficRulesPtr;
289 
290  [[nodiscard]] static auto routeCache(const RoutingGraphType type) -> RouteCache &;
291  [[nodiscard]] static auto centerPointsCache() -> CenterPointsCache &;
292  [[nodiscard]] static auto laneletLengthCache() -> LaneletLengthCache &;
293 
294 private:
295  explicit LaneletWrapper(const std::filesystem::path & lanelet_map_path);
296  static LaneletWrapper & getInstance();
297 
298  inline static std::unique_ptr<LaneletWrapper> instance{nullptr};
299  inline static std::string lanelet_map_path_{""};
300  inline static std::mutex mutex_;
301 
302  const lanelet::LaneletMapPtr lanelet_map_ptr_;
303 
304  const TrafficRulesWithRoutingGraph vehicle_;
305  const TrafficRulesWithRoutingGraph vehicle_with_road_shoulder_;
306  const TrafficRulesWithRoutingGraph pedestrian_;
307 
308  mutable CenterPointsCache center_points_cache_;
309  mutable LaneletLengthCache lanelet_length_cache_;
310 };
311 } // namespace lanelet_wrapper
312 } // namespace traffic_simulator
313 #endif // TRAFFIC_SIMULATOR__LANELET_WRAPPER_HPP_
Definition: catmull_rom_spline_interface.hpp:30
Definition: catmull_rom_spline.hpp:34
Definition: hermite_curve.hpp:32
auto getCenterPointsSpline(const lanelet::Id lanelet_id, const lanelet::LaneletMapPtr &lanelet_map) -> decltype(auto)
Definition: lanelet_wrapper.hpp:159
auto getCenterPoints(const lanelet::Id lanelet_id, const lanelet::LaneletMapPtr &lanelet_map) -> decltype(auto)
Definition: lanelet_wrapper.hpp:150
auto getLength(const lanelet::Id lanelet_id, const lanelet::LaneletMapPtr &lanelet_map) -> double
Definition: lanelet_wrapper.hpp:232
auto getLength(lanelet::Id lanelet_id) -> double
Definition: lanelet_wrapper.hpp:224
Definition: lanelet_wrapper.hpp:280
static auto routingGraph(const RoutingGraphType type) -> lanelet::routing::RoutingGraphConstPtr
Definition: lanelet_wrapper.cpp:34
static auto centerPointsCache() -> CenterPointsCache &
Definition: lanelet_wrapper.cpp:84
static auto routeCache(const RoutingGraphType type) -> RouteCache &
Definition: lanelet_wrapper.cpp:68
static auto activate(const std::string &lanelet_map_path) -> void
Definition: lanelet_wrapper.cpp:23
static auto map() -> lanelet::LaneletMapPtr
Definition: lanelet_wrapper.cpp:32
static auto laneletLengthCache() -> LaneletLengthCache &
Definition: lanelet_wrapper.cpp:89
static auto trafficRules(const RoutingGraphType type) -> lanelet::traffic_rules::TrafficRulesPtr
Definition: lanelet_wrapper.cpp:51
Definition: lanelet_wrapper.hpp:78
auto getRoute(const lanelet::Id from_lanelet_id, const lanelet::Id to_lanelet_id, const lanelet::LaneletMapPtr &lanelet_map, const RoutingConfiguration &routing_configuration, const lanelet::routing::RoutingGraphConstPtr &routing_graph) -> lanelet::Ids
Definition: lanelet_wrapper.hpp:80
auto getRoute(const lanelet::Id from, const lanelet::Id to, const bool allow_lane_change) -> decltype(auto)
Definition: lanelet_wrapper.hpp:108
#define THROW_SIMULATION_ERROR(...)
Definition: exception.hpp:60
Definition: lanelet_wrapper.hpp:43
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:70
traffic_simulator_msgs::msg::BoundingBox BoundingBox
Definition: lanelet_wrapper.hpp:65
traffic_simulator_msgs::msg::LaneletPose LaneletPose
Definition: lanelet_wrapper.hpp:68
geometry_msgs::msg::Point Point
Definition: lanelet_wrapper.hpp:69
traffic_simulator_msgs::msg::EntityType EntityType
Definition: lanelet_wrapper.hpp:67
geometry_msgs::msg::PoseStamped PoseStamped
Definition: lanelet_wrapper.hpp:71
geometry_msgs::msg::Vector3 Vector3
Definition: lanelet_wrapper.hpp:74
RoutingGraphType
Definition: routing_graph_type.hpp:24
Definition: api.hpp:33
std::string string
Definition: junit5.hpp:26
traffic_simulator_msgs::EntityType EntityType
Definition: helper_functions.hpp:31
size_t operator()(const std::tuple< lanelet::Id, lanelet::Id, bool > &data) const
Definition: lanelet_wrapper.hpp:48
Definition: routing_configuration.hpp:24
RouteCache route_cache
Definition: lanelet_wrapper.hpp:268
TrafficRulesWithRoutingGraph(const lanelet::LaneletMapPtr lanelet_map_ptr, const std::string &locations, const std::string &participants)
Definition: lanelet_wrapper.hpp:270
lanelet::traffic_rules::TrafficRulesPtr rules
Definition: lanelet_wrapper.hpp:266
lanelet::routing::RoutingGraphConstPtr graph
Definition: lanelet_wrapper.hpp:267