15 #ifndef TRAFFIC_SIMULATOR__LANELET_WRAPPER_LANELET_MAP_HPP_
16 #define TRAFFIC_SIMULATOR__LANELET_WRAPPER_LANELET_MAP_HPP_
22 namespace lanelet_wrapper
27 auto isInLanelet(
const lanelet::Id lanelet_id,
const double lanelet_pose_s) -> bool;
36 -> std::tuple<double, Point, Point>;
40 const double matching_distance) -> std::optional<double>;
42 template <
typename Lanelet>
43 auto laneletIds(
const std::vector<Lanelet> & lanelets) -> lanelet::Ids
47 lanelets.begin(), lanelets.end(), std::back_inserter(ids),
48 [](
const auto & lanelet) { return lanelet.id(); });
54 auto filterLaneletIds(
const lanelet::Ids & lanelet_ids,
const char subtype[]) -> lanelet::Ids;
57 const Point & point,
const double distance_threshold,
const bool include_crosswalk,
58 const std::size_t search_count) -> lanelet::Ids;
61 auto centerPoints(
const lanelet::Ids & lanelet_ids) -> std::vector<Point>;
63 auto centerPoints(
const lanelet::Id lanelet_id) -> std::vector<Point>;
69 const lanelet::Id lanelet_id,
73 const lanelet::Ids & lanelet_ids,
77 const lanelet::Id lanelet_id, std::string_view turn_direction,
81 const lanelet::Ids & lanelet_ids, std::string_view turn_direction,
86 const lanelet::Id lanelet_id,
90 const lanelet::Ids & lanelet_ids,
94 const lanelet::Id lanelet_id, std::string_view turn_direction,
98 const lanelet::Ids & lanelet_ids, std::string_view turn_direction,
102 auto leftBound(
const lanelet::Id lanelet_id) -> std::vector<Point>;
104 auto rightBound(
const lanelet::Id lanelet_id) -> std::vector<Point>;
107 auto laneletPolygon(
const lanelet::Id lanelet_id) -> std::vector<Point>;
109 auto stopLinePolygon(
const lanelet::Id lanelet_id) -> std::vector<Point>;
111 auto toPolygon(
const lanelet::ConstLineString3d & line_string) -> std::vector<Point>;
115 -> std::unordered_map<lanelet::Id, lanelet::Ids>;
122 const lanelet::Ids & lanelet_ids,
127 -> std::vector<std::shared_ptr<const lanelet::TrafficSign>>;
129 auto trafficSigns() -> std::vector<std::shared_ptr<const lanelet::TrafficSign>>;
131 auto stopLines() -> lanelet::ConstLineStrings3d;
133 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:249
auto laneletPolygon(const lanelet::Id lanelet_id) -> std::vector< Point >
Definition: lanelet_map.cpp:311
auto stopLines() -> lanelet::ConstLineStrings3d
Definition: lanelet_map.cpp:425
auto laneletAltitude(const lanelet::Id &lanelet_id, const geometry_msgs::msg::Pose &pose, const double matching_distance) -> std::optional< double >
Definition: lanelet_map.cpp:73
auto isInIntersection(const lanelet::Id) -> bool
Definition: lanelet_map.cpp:40
auto stopLinesOnPath(const lanelet::Ids &lanelet_ids) -> lanelet::ConstLineStrings3d
Definition: lanelet_map.cpp:437
auto leftBound(const lanelet::Id lanelet_id) -> std::vector< Point >
Definition: lanelet_map.cpp:300
auto conflictingLaneIds(const lanelet::Ids &lanelet_ids, const RoutingGraphType type=RoutingConfiguration().routing_graph_type) -> lanelet::Ids
Definition: lanelet_map.cpp:383
auto stopLineIds() -> lanelet::Ids
Definition: lanelet_map.cpp:449
auto stopLinePolygon(const lanelet::Id lanelet_id) -> std::vector< Point >
Definition: lanelet_map.cpp:322
auto rightBound(const lanelet::Id lanelet_id) -> std::vector< Point >
Definition: lanelet_map.cpp:305
auto nextLaneletIds(const lanelet::Id lanelet_id, const RoutingGraphType type=RoutingConfiguration().routing_graph_type) -> lanelet::Ids
Definition: lanelet_map.cpp:199
auto centerPointsSpline(const lanelet::Id lanelet_id) -> std::shared_ptr< Spline >
Definition: lanelet_map.cpp:192
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:120
auto trafficSigns() -> std::vector< std::shared_ptr< const lanelet::TrafficSign >>
Definition: lanelet_map.cpp:412
auto rightOfWayLaneletIds(const lanelet::Ids &lanelet_ids) -> std::unordered_map< lanelet::Id, lanelet::Ids >
Definition: lanelet_map.cpp:354
auto laneletYaw(const lanelet::Id lanelet_id, const Point &point) -> std::tuple< double, Point, Point >
Definition: lanelet_map.cpp:50
auto filterLaneletIds(const lanelet::Ids &lanelet_ids, const char subtype[]) -> lanelet::Ids
Definition: lanelet_map.cpp:96
auto laneletIds(const std::vector< Lanelet > &lanelets) -> lanelet::Ids
Definition: lanelet_map.hpp:43
auto stopLineIdsOnPath(const lanelet::Ids &lanelet_ids) -> lanelet::Ids
Definition: lanelet_map.cpp:460
auto isInLanelet(const lanelet::Id lanelet_id, const double lanelet_pose_s) -> bool
Definition: lanelet_map.cpp:29
auto conflictingCrosswalkIds(const lanelet::Ids &lanelet_ids) -> lanelet::Ids
Definition: lanelet_map.cpp:364
auto toPolygon(const lanelet::ConstLineString3d &line_string) -> std::vector< Point >
Definition: lanelet_map.cpp:328
auto laneletLength(const lanelet::Id lanelet_id) -> double
Definition: lanelet_map.cpp:45
auto centerPoints(const lanelet::Ids &lanelet_ids) -> std::vector< Point >
Definition: lanelet_map.cpp:170
auto trafficSignsOnPath(const lanelet::Ids &lanelet_ids) -> std::vector< std::shared_ptr< const lanelet::TrafficSign >>
Definition: lanelet_map.cpp:398
geometry_msgs::msg::Point Point
Definition: lanelet_wrapper.hpp:69
RoutingGraphType
Definition: routing_graph_type.hpp:24
Definition: routing_configuration.hpp:24