15 #ifndef TRAFFIC_SIMULATOR__LANELET_WRAPPER_HPP_
16 #define TRAFFIC_SIMULATOR__LANELET_WRAPPER_HPP_
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>
25 #include <autoware_lanelet2_extension/utility/utilities.hpp>
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>
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>
45 struct hash<
std::tuple<lanelet::Id, lanelet::Id, bool>>
48 size_t operator()(
const std::tuple<lanelet::Id, lanelet::Id, bool> & data)
const
50 std::hash<lanelet::Id> lanelet_id_hash;
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);
63 namespace lanelet_wrapper
80 const lanelet::Id from_lanelet_id,
const lanelet::Id to_lanelet_id,
82 const lanelet::routing::RoutingGraphConstPtr & routing_graph) -> lanelet::Ids
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);
93 from_lanelet_id, to_lanelet_id, routing_configuration.allow_lane_change, lanelet::Ids());
95 lanelet::Ids shortest_path_ids;
96 for (
const auto & lanelet :
route->shortestPath()) {
97 shortest_path_ids.push_back(lanelet.id());
100 from_lanelet_id, to_lanelet_id, routing_configuration.allow_lane_change,
104 return readData(from_lanelet_id, to_lanelet_id, routing_configuration.allow_lane_change);
107 auto getRoute(
const lanelet::Id from,
const lanelet::Id to,
const bool allow_lane_change)
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.");
115 return readData(from, to, allow_lane_change);
120 auto exists(
const lanelet::Id from,
const lanelet::Id to,
const bool allow_lane_change) ->
bool
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();
127 auto readData(
const lanelet::Id from,
const lanelet::Id to,
const bool allow_lane_change)
130 std::lock_guard lock(mutex_);
131 return data_.at({from, to, allow_lane_change});
135 const lanelet::Id from,
const lanelet::Id to,
const bool allow_lane_change,
136 const lanelet::Ids &
route) ->
void
138 std::lock_guard lock(mutex_);
139 data_[{from, to, allow_lane_change}] =
route;
142 std::unordered_map<std::tuple<lanelet::Id, lanelet::Id, bool>, lanelet::Ids> data_;
151 if (!exists(lanelet_id)) {
154 return readData(lanelet_id);
159 if (!exists(lanelet_id)) {
162 return readDataSpline(lanelet_id);
165 auto getCenterPoints(
const lanelet::Id lanelet_id,
const lanelet::LaneletMapPtr & lanelet_map)
168 if (!exists(lanelet_id)) {
169 appendData(lanelet_id,
centerPoints(lanelet_id, lanelet_map));
171 return readData(lanelet_id);
175 const lanelet::Id lanelet_id,
const lanelet::LaneletMapPtr & lanelet_map) -> decltype(
auto)
177 if (!exists(lanelet_id)) {
178 appendData(lanelet_id,
centerPoints(lanelet_id, lanelet_map));
180 return readDataSpline(lanelet_id);
184 auto exists(
const lanelet::Id lanelet_id) ->
bool
186 std::lock_guard lock(mutex_);
187 return data_.find(lanelet_id) != data_.end();
190 auto readData(
const lanelet::Id lanelet_id) ->
const std::vector<Point> &
192 std::lock_guard lock(mutex_);
193 return data_.at(lanelet_id);
196 auto readDataSpline(
const lanelet::Id lanelet_id) -> std::shared_ptr<Spline>
198 std::lock_guard lock(mutex_);
199 return splines_.at(lanelet_id);
202 auto appendData(
const lanelet::Id lanelet_id,
const std::vector<Point> &
route) ->
void
204 std::lock_guard lock(mutex_);
205 data_[lanelet_id] =
route;
206 splines_[lanelet_id] = std::make_shared<Spline>(
route);
209 auto centerPoints(
const lanelet::Id lanelet_id,
const lanelet::LaneletMapPtr & lanelet_map)
const
210 -> std::vector<Point>
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()));
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);
228 return center_points;
231 std::unordered_map<lanelet::Id, std::vector<Point>> data_;
232 std::unordered_map<lanelet::Id, std::shared_ptr<Spline>> splines_;
241 if (!exists(lanelet_id)) {
244 return readData(lanelet_id);
247 auto getLength(
const lanelet::Id lanelet_id,
const lanelet::LaneletMapPtr & lanelet_map) ->
double
249 if (!exists(lanelet_id)) {
251 lanelet_id, lanelet::utils::getLaneletLength2d(lanelet_map->laneletLayer.get(lanelet_id)));
253 return readData(lanelet_id);
257 auto exists(
const lanelet::Id lanelet_id) ->
bool
259 std::lock_guard lock(mutex_);
260 return data_.find(lanelet_id) != data_.end();
263 auto readData(
const lanelet::Id lanelet_id) ->
double
265 std::lock_guard lock(mutex_);
266 return data_.at(lanelet_id);
269 auto appendData(
const lanelet::Id lanelet_id,
double length) ->
void
271 std::lock_guard lock(mutex_);
272 data_[lanelet_id] = length;
275 std::unordered_map<lanelet::Id, double> data_;
281 lanelet::traffic_rules::TrafficRulesPtr
rules;
282 lanelet::routing::RoutingGraphConstPtr
graph;
286 const lanelet::LaneletMapPtr lanelet_map_ptr,
const std::string & locations,
289 rules = lanelet::traffic_rules::TrafficRulesFactory::create(locations, participants);
290 graph = lanelet::routing::RoutingGraph::build(*lanelet_map_ptr, *
rules);
299 [[nodiscard]]
static auto map() -> lanelet::LaneletMapPtr;
301 -> lanelet::routing::RoutingGraphConstPtr;
303 -> lanelet::traffic_rules::TrafficRulesPtr;
310 explicit LaneletWrapper(
const std::filesystem::path & lanelet_map_path);
313 inline static std::unique_ptr<LaneletWrapper> instance{
nullptr};
315 inline static std::mutex mutex_;
317 const lanelet::LaneletMapPtr lanelet_map_ptr_;
Definition: catmull_rom_spline_interface.hpp:30
Definition: catmull_rom_spline.hpp:34
Definition: lanelet_wrapper.hpp:147
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
Definition: lanelet_wrapper.hpp:237
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
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
Definition: lanelet_wrapper.hpp:280
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