15 #ifndef TRAFFIC_SIMULATOR__HDMAP_UTILS__CACHE_HPP_
16 #define TRAFFIC_SIMULATOR__HDMAP_UTILS__CACHE_HPP_
19 #include <geometry_msgs/msg/point.hpp>
24 #include <unordered_map>
32 auto exists(lanelet::Id from, lanelet::Id to,
bool allow_lane_change)
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();
39 auto getRoute(
const lanelet::Id from,
const lanelet::Id to,
const bool allow_lane_change)
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.");
47 std::lock_guard lock(mutex_);
48 return data_.at({from, to, allow_lane_change});
53 lanelet::Id from, lanelet::Id to,
const bool allow_lane_change,
const lanelet::Ids &
route)
56 std::lock_guard lock(mutex_);
57 data_[{from, to, allow_lane_change}] =
route;
61 std::unordered_map<std::tuple<lanelet::Id, lanelet::Id, bool>, lanelet::Ids> data_;
69 auto exists(lanelet::Id lanelet_id) ->
bool
71 std::lock_guard lock(mutex_);
72 return data_.find(lanelet_id) != data_.end();
80 std::lock_guard lock(mutex_);
81 return data_.at(lanelet_id);
89 std::lock_guard lock(mutex_);
90 return splines_[lanelet_id];
93 auto appendData(lanelet::Id lanelet_id,
const std::vector<geometry_msgs::msg::Point> &
route)
95 std::lock_guard lock(mutex_);
96 data_[lanelet_id] =
route;
97 splines_[lanelet_id] = std::make_shared<math::geometry::CatmullRomSpline>(
route);
101 std::unordered_map<lanelet::Id, std::vector<geometry_msgs::msg::Point>> data_;
103 std::unordered_map<lanelet::Id, std::shared_ptr<math::geometry::CatmullRomSpline>> splines_;
113 std::lock_guard lock(mutex_);
114 return data_.find(lanelet_id) != data_.end();
119 if (!
exists(lanelet_id)) {
122 std::lock_guard lock(mutex_);
123 return data_[lanelet_id];
128 std::lock_guard lock(mutex_);
129 data_[lanelet_id] = length;
133 std::unordered_map<lanelet::Id, double> data_;
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
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
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