15 #ifndef TRAFFIC_SIMULATOR__LANELET_WRAPPER_LANELET_MAP_HPP_
16 #define TRAFFIC_SIMULATOR__LANELET_WRAPPER_LANELET_MAP_HPP_
18 #include <lanelet2_core/geometry/Lanelet.h>
19 #include <lanelet2_core/primitives/LaneletSequence.h>
25 namespace lanelet_wrapper
29 auto isInLanelet(
const lanelet::Id lanelet_id,
const double lanelet_pose_s) -> bool;
37 const double matching_distance) -> std::optional<double>;
39 template <
typename Lanelet>
40 auto laneletIds(
const std::vector<Lanelet> & lanelets) -> lanelet::Ids
44 lanelets.begin(), lanelets.end(), std::back_inserter(ids),
45 [](
const auto & lanelet) { return lanelet.id(); });
52 const Point & point,
const double distance_threshold,
const bool include_crosswalk,
53 const std::size_t search_count) -> lanelet::Ids;
55 auto centerPoints(
const lanelet::Ids & lanelet_ids) -> std::vector<Point>;
57 auto centerPoints(
const lanelet::Id lanelet_id) -> std::vector<Point>;
62 const lanelet::Id lanelet_id,
66 const lanelet::Ids & lanelet_ids,
70 const lanelet::Id lanelet_id, std::string_view turn_direction,
74 const lanelet::Ids & lanelet_ids, std::string_view turn_direction,
78 const lanelet::Id lanelet_id,
82 const lanelet::Ids & lanelet_ids,
86 const lanelet::Id lanelet_id, std::string_view turn_direction,
90 const lanelet::Ids & lanelet_ids, std::string_view turn_direction,
geometry_msgs::msg::Pose Pose
Definition: lanelet_map.hpp:30
auto previousLaneletIds(const lanelet::Id lanelet_id, const RoutingGraphType type=RoutingConfiguration().routing_graph_type) -> lanelet::Ids
Definition: lanelet_map.cpp:191
auto laneletAltitude(const lanelet::Id &lanelet_id, const geometry_msgs::msg::Pose &pose, const double matching_distance) -> std::optional< double >
Definition: lanelet_map.cpp:47
auto nextLaneletIds(const lanelet::Id lanelet_id, const RoutingGraphType type=RoutingConfiguration().routing_graph_type) -> lanelet::Ids
Definition: lanelet_map.cpp:144
auto centerPointsSpline(const lanelet::Id lanelet_id) -> std::shared_ptr< Spline >
Definition: lanelet_map.cpp:138
auto nearbyLaneletIds(const Point &point, const double distance_threshold, const bool include_crosswalk, const std::size_t search_count) -> lanelet::Ids
Definition: lanelet_map.cpp:68
auto laneletIds(const std::vector< Lanelet > &lanelets) -> lanelet::Ids
Definition: lanelet_map.hpp:40
auto isInLanelet(const lanelet::Id lanelet_id, const double lanelet_pose_s) -> bool
Definition: lanelet_map.cpp:31
auto laneletLength(const lanelet::Id lanelet_id) -> double
Definition: lanelet_map.cpp:42
auto centerPoints(const lanelet::Ids &lanelet_ids) -> std::vector< Point >
Definition: lanelet_map.cpp:117
geometry_msgs::msg::Point Point
Definition: lanelet_wrapper.hpp:64
RoutingGraphType
Definition: routing_graph_type.hpp:24
Definition: routing_configuration.hpp:24