scenario_simulator_v2 C++ API
cache.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__CACHE_HPP_
16 #define TRAFFIC_SIMULATOR__HDMAP_UTILS__CACHE_HPP_
17 
19 #include <geometry_msgs/msg/point.hpp>
20 #include <mutex>
21 #include <optional>
24 #include <unordered_map>
25 #include <vector>
26 
27 namespace hdmap_utils
28 {
30 {
31 public:
32  auto exists(lanelet::Id from, lanelet::Id to, bool allow_lane_change)
33  {
34  std::lock_guard lock(mutex_);
35  std::tuple<lanelet::Id, lanelet::Id, bool> key = {from, to, allow_lane_change};
36  return data_.find(key) != data_.end();
37  }
38 
39  auto getRoute(const lanelet::Id from, const lanelet::Id to, const bool allow_lane_change)
40  -> decltype(auto)
41  {
42  if (!exists(from, to, allow_lane_change)) {
44  "route from : ", from, " to : ", to, (allow_lane_change ? " with" : " without"),
45  " lane change does not exists on route cache.");
46  } else {
47  std::lock_guard lock(mutex_);
48  return data_.at({from, to, allow_lane_change});
49  }
50  }
51 
52  auto appendData(
53  lanelet::Id from, lanelet::Id to, const bool allow_lane_change, const lanelet::Ids & route)
54  -> void
55  {
56  std::lock_guard lock(mutex_);
57  data_[{from, to, allow_lane_change}] = route;
58  }
59 
60 private:
61  std::unordered_map<std::tuple<lanelet::Id, lanelet::Id, bool>, lanelet::Ids> data_;
62 
63  std::mutex mutex_;
64 };
65 
67 {
68 public:
69  auto exists(lanelet::Id lanelet_id) -> bool
70  {
71  std::lock_guard lock(mutex_);
72  return data_.find(lanelet_id) != data_.end();
73  }
74 
75  auto getCenterPoints(lanelet::Id lanelet_id) -> decltype(auto)
76  {
77  if (!exists(lanelet_id)) {
78  THROW_SIMULATION_ERROR("center point of : ", lanelet_id, " does not exists on route cache.");
79  }
80  std::lock_guard lock(mutex_);
81  return data_.at(lanelet_id);
82  }
83 
84  auto getCenterPointsSpline(lanelet::Id lanelet_id) -> decltype(auto)
85  {
86  if (!exists(lanelet_id)) {
87  THROW_SIMULATION_ERROR("center point of : ", lanelet_id, " does not exists on route cache.");
88  }
89  std::lock_guard lock(mutex_);
90  return splines_[lanelet_id];
91  }
92 
93  auto appendData(lanelet::Id lanelet_id, const std::vector<geometry_msgs::msg::Point> & route)
94  {
95  std::lock_guard lock(mutex_);
96  data_[lanelet_id] = route;
97  splines_[lanelet_id] = std::make_shared<math::geometry::CatmullRomSpline>(route);
98  }
99 
100 private:
101  std::unordered_map<lanelet::Id, std::vector<geometry_msgs::msg::Point>> data_;
102 
103  std::unordered_map<lanelet::Id, std::shared_ptr<math::geometry::CatmullRomSpline>> splines_;
104 
105  std::mutex mutex_;
106 };
107 
109 {
110 public:
111  auto exists(lanelet::Id lanelet_id)
112  {
113  std::lock_guard lock(mutex_);
114  return data_.find(lanelet_id) != data_.end();
115  }
116 
117  auto getLength(lanelet::Id lanelet_id)
118  {
119  if (!exists(lanelet_id)) {
120  THROW_SIMULATION_ERROR("length of : ", lanelet_id, " does not exists on route cache.");
121  }
122  std::lock_guard lock(mutex_);
123  return data_[lanelet_id];
124  }
125 
126  auto appendData(lanelet::Id lanelet_id, double length)
127  {
128  std::lock_guard lock(mutex_);
129  data_[lanelet_id] = length;
130  }
131 
132 private:
133  std::unordered_map<lanelet::Id, double> data_;
134 
135  std::mutex mutex_;
136 };
137 } // namespace hdmap_utils
138 
139 #endif // TRAFFIC_SIMULATOR__HDMAP_UTILS__CACHE_HPP_
Definition: cache.hpp:67
auto getCenterPoints(lanelet::Id lanelet_id) -> decltype(auto)
Definition: cache.hpp:75
auto getCenterPointsSpline(lanelet::Id lanelet_id) -> decltype(auto)
Definition: cache.hpp:84
auto appendData(lanelet::Id lanelet_id, const std::vector< geometry_msgs::msg::Point > &route)
Definition: cache.hpp:93
auto exists(lanelet::Id lanelet_id) -> bool
Definition: cache.hpp:69
Definition: cache.hpp:109
auto appendData(lanelet::Id lanelet_id, double length)
Definition: cache.hpp:126
auto getLength(lanelet::Id lanelet_id)
Definition: cache.hpp:117
auto exists(lanelet::Id lanelet_id)
Definition: cache.hpp:111
Definition: cache.hpp:30
auto exists(lanelet::Id from, lanelet::Id to, bool allow_lane_change)
Definition: cache.hpp:32
auto appendData(lanelet::Id from, lanelet::Id to, const bool allow_lane_change, const lanelet::Ids &route) -> void
Definition: cache.hpp:52
auto getRoute(const lanelet::Id from, const lanelet::Id to, const bool allow_lane_change) -> decltype(auto)
Definition: cache.hpp:39
#define THROW_SIMULATION_ERROR(...)
Definition: exception.hpp:60
Definition: cache.hpp:28
auto route(const lanelet::Id from_lanelet_id, const lanelet::Id to_lanelet_id, const RoutingConfiguration &routing_configuration=RoutingConfiguration()) -> lanelet::Ids
Definition: route.cpp:33