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 {
75 
77 {
78 public:
79  auto getRoute(
80  const lanelet::Id from_lanelet_id, const lanelet::Id to_lanelet_id,
81  const lanelet::LaneletMapPtr & lanelet_map, const RoutingConfiguration & routing_configuration,
82  const lanelet::routing::RoutingGraphConstPtr & routing_graph) -> lanelet::Ids
83  {
84  if (!exists(from_lanelet_id, to_lanelet_id, routing_configuration.allow_lane_change)) {
86  constexpr int routing_cost_id = 0;
87  const auto & from_lanelet = lanelet_map->laneletLayer.get(from_lanelet_id);
88  const auto & to_lanelet = lanelet_map->laneletLayer.get(to_lanelet_id);
89  if (const auto route = routing_graph->getRoute(
90  from_lanelet, to_lanelet, routing_cost_id, routing_configuration.allow_lane_change);
91  !route || route->shortestPath().empty()) {
92  appendData(
93  from_lanelet_id, to_lanelet_id, routing_configuration.allow_lane_change, lanelet::Ids());
94  } else {
95  lanelet::Ids shortest_path_ids;
96  for (const auto & lanelet : route->shortestPath()) {
97  shortest_path_ids.push_back(lanelet.id());
98  }
99  appendData(
100  from_lanelet_id, to_lanelet_id, routing_configuration.allow_lane_change,
101  shortest_path_ids);
102  }
103  }
104  return readData(from_lanelet_id, to_lanelet_id, routing_configuration.allow_lane_change);
105  }
106 
107  auto getRoute(const lanelet::Id from, const lanelet::Id to, const bool allow_lane_change)
108  -> decltype(auto)
109  {
110  if (!exists(from, to, allow_lane_change)) {
112  "route from : ", from, " to : ", to, (allow_lane_change ? " with" : " without"),
113  " lane change does not exists on route cache.");
114  } else {
115  return readData(from, to, allow_lane_change);
116  }
117  }
118 
119 private:
120  auto exists(const lanelet::Id from, const lanelet::Id to, const bool allow_lane_change) -> bool
121  {
122  std::lock_guard lock(mutex_);
123  std::tuple<lanelet::Id, lanelet::Id, bool> key = {from, to, allow_lane_change};
124  return data_.find(key) != data_.end();
125  }
126 
127  auto readData(const lanelet::Id from, const lanelet::Id to, const bool allow_lane_change)
128  -> lanelet::Ids
129  {
130  std::lock_guard lock(mutex_);
131  return data_.at({from, to, allow_lane_change});
132  }
133 
134  auto appendData(
135  const lanelet::Id from, const lanelet::Id to, const bool allow_lane_change,
136  const lanelet::Ids & route) -> void
137  {
138  std::lock_guard lock(mutex_);
139  data_[{from, to, allow_lane_change}] = route;
140  }
141 
142  std::unordered_map<std::tuple<lanelet::Id, lanelet::Id, bool>, lanelet::Ids> data_;
143  std::mutex mutex_;
144 };
145 
147 {
148 public:
149  auto centerPoints(lanelet::Id lanelet_id) -> decltype(auto)
150  {
151  if (!exists(lanelet_id)) {
152  THROW_SIMULATION_ERROR("center point of : ", lanelet_id, " does not exists on route cache.");
153  }
154  return readData(lanelet_id);
155  }
156 
157  auto centerPointsSpline(lanelet::Id lanelet_id) -> decltype(auto)
158  {
159  if (!exists(lanelet_id)) {
160  THROW_SIMULATION_ERROR("center point of : ", lanelet_id, " does not exists on route cache.");
161  }
162  return readDataSpline(lanelet_id);
163  }
164 
165  auto getCenterPoints(const lanelet::Id lanelet_id, const lanelet::LaneletMapPtr & lanelet_map)
166  -> decltype(auto)
167  {
168  if (!exists(lanelet_id)) {
169  appendData(lanelet_id, centerPoints(lanelet_id, lanelet_map));
170  }
171  return readData(lanelet_id);
172  }
173 
175  const lanelet::Id lanelet_id, const lanelet::LaneletMapPtr & lanelet_map) -> decltype(auto)
176  {
177  if (!exists(lanelet_id)) {
178  appendData(lanelet_id, centerPoints(lanelet_id, lanelet_map));
179  }
180  return readDataSpline(lanelet_id);
181  }
182 
183 private:
184  auto exists(const lanelet::Id lanelet_id) -> bool
185  {
186  std::lock_guard lock(mutex_);
187  return data_.find(lanelet_id) != data_.end();
188  }
189 
190  auto readData(const lanelet::Id lanelet_id) -> const std::vector<Point> &
191  {
192  std::lock_guard lock(mutex_);
193  return data_.at(lanelet_id);
194  }
195 
196  auto readDataSpline(const lanelet::Id lanelet_id) -> std::shared_ptr<Spline>
197  {
198  std::lock_guard lock(mutex_);
199  return splines_.at(lanelet_id);
200  }
201 
202  auto appendData(const lanelet::Id lanelet_id, const std::vector<Point> & route) -> void
203  {
204  std::lock_guard lock(mutex_);
205  data_[lanelet_id] = route;
206  splines_[lanelet_id] = std::make_shared<Spline>(route);
207  }
208 
209  auto centerPoints(const lanelet::Id lanelet_id, const lanelet::LaneletMapPtr & lanelet_map) const
210  -> std::vector<Point>
211  {
212  std::vector<Point> center_points;
213  for (const auto & point : lanelet_map->laneletLayer.get(lanelet_id).centerline()) {
214  center_points.push_back(geometry_msgs::build<Point>().x(point.x()).y(point.y()).z(point.z()));
215  }
216  if (center_points.size() == 2) {
217  const auto p0 = center_points[0];
218  const auto p2 = center_points[1];
219  const auto p1 = geometry_msgs::build<Point>()
220  .x((p0.x + p2.x) * 0.5)
221  .y((p0.y + p2.y) * 0.5)
222  .z((p0.z + p2.z) * 0.5);
223  center_points.clear();
224  center_points.push_back(p0);
225  center_points.push_back(p1);
226  center_points.push_back(p2);
227  }
228  return center_points;
229  }
230 
231  std::unordered_map<lanelet::Id, std::vector<Point>> data_;
232  std::unordered_map<lanelet::Id, std::shared_ptr<Spline>> splines_;
233  std::mutex mutex_;
234 };
235 
237 {
238 public:
239  auto getLength(lanelet::Id lanelet_id) -> double
240  {
241  if (!exists(lanelet_id)) {
242  THROW_SIMULATION_ERROR("length of : ", lanelet_id, " does not exists on route cache.");
243  }
244  return readData(lanelet_id);
245  }
246 
247  auto getLength(const lanelet::Id lanelet_id, const lanelet::LaneletMapPtr & lanelet_map) -> double
248  {
249  if (!exists(lanelet_id)) {
250  appendData(
251  lanelet_id, lanelet::utils::getLaneletLength2d(lanelet_map->laneletLayer.get(lanelet_id)));
252  }
253  return readData(lanelet_id);
254  }
255 
256 private:
257  auto exists(const lanelet::Id lanelet_id) -> bool
258  {
259  std::lock_guard lock(mutex_);
260  return data_.find(lanelet_id) != data_.end();
261  }
262 
263  auto readData(const lanelet::Id lanelet_id) -> double
264  {
265  std::lock_guard lock(mutex_);
266  return data_.at(lanelet_id);
267  }
268 
269  auto appendData(const lanelet::Id lanelet_id, double length) -> void
270  {
271  std::lock_guard lock(mutex_);
272  data_[lanelet_id] = length;
273  }
274 
275  std::unordered_map<lanelet::Id, double> data_;
276  std::mutex mutex_;
277 };
278 
280 {
281  lanelet::traffic_rules::TrafficRulesPtr rules;
282  lanelet::routing::RoutingGraphConstPtr graph;
284 
286  const lanelet::LaneletMapPtr lanelet_map_ptr, const std::string & locations,
287  const std::string & participants)
288  {
289  rules = lanelet::traffic_rules::TrafficRulesFactory::create(locations, participants);
290  graph = lanelet::routing::RoutingGraph::build(*lanelet_map_ptr, *rules);
291  }
292 };
293 
295 {
296 public:
297  static auto activate(const std::string & lanelet_map_path) -> void;
298 
299  [[nodiscard]] static auto map() -> lanelet::LaneletMapPtr;
300  [[nodiscard]] static auto routingGraph(const RoutingGraphType type)
301  -> lanelet::routing::RoutingGraphConstPtr;
302  [[nodiscard]] static auto trafficRules(const RoutingGraphType type)
303  -> lanelet::traffic_rules::TrafficRulesPtr;
304 
305  [[nodiscard]] static auto routeCache(const RoutingGraphType type) -> RouteCache &;
306  [[nodiscard]] static auto centerPointsCache() -> CenterPointsCache &;
307  [[nodiscard]] static auto laneletLengthCache() -> LaneletLengthCache &;
308 
309 private:
310  explicit LaneletWrapper(const std::filesystem::path & lanelet_map_path);
311  static LaneletWrapper & getInstance();
312 
313  inline static std::unique_ptr<LaneletWrapper> instance{nullptr};
314  inline static std::string lanelet_map_path_{""};
315  inline static std::mutex mutex_;
316 
317  const lanelet::LaneletMapPtr lanelet_map_ptr_;
318 
319  const TrafficRulesWithRoutingGraph vehicle_;
320  const TrafficRulesWithRoutingGraph vehicle_with_road_shoulder_;
321  const TrafficRulesWithRoutingGraph pedestrian_;
322 
323  mutable CenterPointsCache center_points_cache_;
324  mutable LaneletLengthCache lanelet_length_cache_;
325 };
326 } // namespace lanelet_wrapper
327 } // namespace traffic_simulator
328 #endif // TRAFFIC_SIMULATOR__LANELET_WRAPPER_HPP_
Definition: catmull_rom_spline_interface.hpp:30
Definition: catmull_rom_spline.hpp:34
auto centerPointsSpline(lanelet::Id lanelet_id) -> decltype(auto)
Definition: lanelet_wrapper.hpp:157
auto centerPoints(lanelet::Id lanelet_id) -> decltype(auto)
Definition: lanelet_wrapper.hpp:149
auto getCenterPointsSpline(const lanelet::Id lanelet_id, const lanelet::LaneletMapPtr &lanelet_map) -> decltype(auto)
Definition: lanelet_wrapper.hpp:174
auto getCenterPoints(const lanelet::Id lanelet_id, const lanelet::LaneletMapPtr &lanelet_map) -> decltype(auto)
Definition: lanelet_wrapper.hpp:165
auto getLength(const lanelet::Id lanelet_id, const lanelet::LaneletMapPtr &lanelet_map) -> double
Definition: lanelet_wrapper.hpp:247
auto getLength(lanelet::Id lanelet_id) -> double
Definition: lanelet_wrapper.hpp:239
Definition: lanelet_wrapper.hpp:295
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:77
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:79
auto getRoute(const lanelet::Id from, const lanelet::Id to, const bool allow_lane_change) -> decltype(auto)
Definition: lanelet_wrapper.hpp:107
#define THROW_SIMULATION_ERROR(...)
Definition: exception.hpp:60
Definition: lanelet_wrapper.hpp:43
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:69
traffic_simulator_msgs::msg::BoundingBox BoundingBox
Definition: lanelet_wrapper.hpp:65
traffic_simulator_msgs::msg::LaneletPose LaneletPose
Definition: lanelet_wrapper.hpp:67
geometry_msgs::msg::Point Point
Definition: lanelet_wrapper.hpp:68
traffic_simulator_msgs::msg::EntityType EntityType
Definition: lanelet_wrapper.hpp:66
geometry_msgs::msg::PoseStamped PoseStamped
Definition: lanelet_wrapper.hpp:70
geometry_msgs::msg::Vector3 Vector3
Definition: lanelet_wrapper.hpp:73
auto route(Ts &&... xs)
Definition: route.hpp:30
RoutingGraphType
Definition: routing_graph_type.hpp:24
Definition: api.hpp:32
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:283
TrafficRulesWithRoutingGraph(const lanelet::LaneletMapPtr lanelet_map_ptr, const std::string &locations, const std::string &participants)
Definition: lanelet_wrapper.hpp:285
lanelet::traffic_rules::TrafficRulesPtr rules
Definition: lanelet_wrapper.hpp:281
lanelet::routing::RoutingGraphConstPtr graph
Definition: lanelet_wrapper.hpp:282