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
30 auto isInLanelet(
const lanelet::Id lanelet_id,
const double lanelet_pose_s) -> bool;
38 const double matching_distance) -> std::optional<double>;
40 template <
typename Lanelet>
41 auto laneletIds(
const std::vector<Lanelet> & lanelets) -> lanelet::Ids
45 lanelets.begin(), lanelets.end(), std::back_inserter(ids),
46 [](
const auto & lanelet) { return lanelet.id(); });
53 const Point & point,
const double distance_threshold,
const bool include_crosswalk,
54 const std::size_t search_count) -> lanelet::Ids;
57 auto centerPoints(
const lanelet::Ids & lanelet_ids) -> std::vector<Point>;
59 auto centerPoints(
const lanelet::Id lanelet_id) -> std::vector<Point>;
65 const lanelet::Id lanelet_id,
69 const lanelet::Ids & lanelet_ids,
73 const lanelet::Id lanelet_id, std::string_view turn_direction,
77 const lanelet::Ids & lanelet_ids, std::string_view turn_direction,
82 const lanelet::Id lanelet_id,
86 const lanelet::Ids & lanelet_ids,
90 const lanelet::Id lanelet_id, std::string_view turn_direction,
94 const lanelet::Ids & lanelet_ids, std::string_view turn_direction,
98 auto leftBound(
const lanelet::Id lanelet_id) -> std::vector<Point>;
100 auto rightBound(
const lanelet::Id lanelet_id) -> std::vector<Point>;
103 auto laneletPolygon(
const lanelet::Id lanelet_id) -> std::vector<Point>;
105 auto stopLinePolygon(
const lanelet::Id lanelet_id) -> std::vector<Point>;
107 auto toPolygon(
const lanelet::ConstLineString3d & line_string) -> std::vector<Point>;
111 -> std::unordered_map<lanelet::Id, lanelet::Ids>;
118 const lanelet::Ids & lanelet_ids,
123 -> std::vector<std::shared_ptr<const lanelet::TrafficSign>>;
125 auto trafficSigns() -> std::vector<std::shared_ptr<const lanelet::TrafficSign>>;
127 auto stopLines() -> lanelet::ConstLineStrings3d;
129 auto stopLinesOnPath(
const lanelet::Ids & lanelet_ids) -> lanelet::ConstLineStrings3d;
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:200
auto laneletPolygon(const lanelet::Id lanelet_id) -> std::vector< Point >
Definition: lanelet_map.cpp:262
auto stopLines() -> lanelet::ConstLineStrings3d
Definition: lanelet_map.cpp:376
auto laneletAltitude(const lanelet::Id &lanelet_id, const geometry_msgs::msg::Pose &pose, const double matching_distance) -> std::optional< double >
Definition: lanelet_map.cpp:48
auto stopLinesOnPath(const lanelet::Ids &lanelet_ids) -> lanelet::ConstLineStrings3d
Definition: lanelet_map.cpp:388
auto leftBound(const lanelet::Id lanelet_id) -> std::vector< Point >
Definition: lanelet_map.cpp:251
auto conflictingLaneIds(const lanelet::Ids &lanelet_ids, const RoutingGraphType type=RoutingConfiguration().routing_graph_type) -> lanelet::Ids
Definition: lanelet_map.cpp:334
auto stopLineIds() -> lanelet::Ids
Definition: lanelet_map.cpp:400
auto stopLinePolygon(const lanelet::Id lanelet_id) -> std::vector< Point >
Definition: lanelet_map.cpp:273
auto rightBound(const lanelet::Id lanelet_id) -> std::vector< Point >
Definition: lanelet_map.cpp:256
auto nextLaneletIds(const lanelet::Id lanelet_id, const RoutingGraphType type=RoutingConfiguration().routing_graph_type) -> lanelet::Ids
Definition: lanelet_map.cpp:150
auto centerPointsSpline(const lanelet::Id lanelet_id) -> std::shared_ptr< Spline >
Definition: lanelet_map.cpp:143
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:71
auto trafficSigns() -> std::vector< std::shared_ptr< const lanelet::TrafficSign >>
Definition: lanelet_map.cpp:363
auto rightOfWayLaneletIds(const lanelet::Ids &lanelet_ids) -> std::unordered_map< lanelet::Id, lanelet::Ids >
Definition: lanelet_map.cpp:305
auto laneletIds(const std::vector< Lanelet > &lanelets) -> lanelet::Ids
Definition: lanelet_map.hpp:41
auto stopLineIdsOnPath(const lanelet::Ids &lanelet_ids) -> lanelet::Ids
Definition: lanelet_map.cpp:411
auto isInLanelet(const lanelet::Id lanelet_id, const double lanelet_pose_s) -> bool
Definition: lanelet_map.cpp:32
auto conflictingCrosswalkIds(const lanelet::Ids &lanelet_ids) -> lanelet::Ids
Definition: lanelet_map.cpp:315
auto toPolygon(const lanelet::ConstLineString3d &line_string) -> std::vector< Point >
Definition: lanelet_map.cpp:279
auto laneletLength(const lanelet::Id lanelet_id) -> double
Definition: lanelet_map.cpp:43
auto centerPoints(const lanelet::Ids &lanelet_ids) -> std::vector< Point >
Definition: lanelet_map.cpp:121
auto trafficSignsOnPath(const lanelet::Ids &lanelet_ids) -> std::vector< std::shared_ptr< const lanelet::TrafficSign >>
Definition: lanelet_map.cpp:349
geometry_msgs::msg::Point Point
Definition: lanelet_wrapper.hpp:65
RoutingGraphType
Definition: routing_graph_type.hpp:24
Definition: routing_configuration.hpp:24