15 #ifndef TRAFFIC_SIMULATOR__UTILS__LANELET_MAP_HPP_
16 #define TRAFFIC_SIMULATOR__UTILS__LANELET_MAP_HPP_
18 #include <autoware_lanelet2_extension/visualization/visualization.hpp>
19 #include <geometry_msgs/msg/point.hpp>
27 inline namespace lanelet_map
32 template <
typename... Ts>
42 const double matching_distance) -> std::optional<double>;
45 const Pose & pose,
const double distance_threshold,
const bool include_crosswalk,
46 const std::size_t search_count = 5) -> lanelet::Ids;
static auto activate(const std::string &lanelet_map_path) -> void
Definition: lanelet_wrapper.cpp:23
auto activate(Ts &&... xs)
Definition: lanelet_map.hpp:33
geometry_msgs::msg::Pose Pose
Definition: lanelet_map.hpp:30
auto nearbyLaneletIds(const Pose &pose, const double distance_threshold, const bool include_crosswalk, const std::size_t search_count=5) -> lanelet::Ids
Definition: lanelet_map.cpp:32
geometry_msgs::msg::Point Point
Definition: lanelet_map.hpp:29
auto laneletAltitude(const lanelet::Id &lanelet_id, const geometry_msgs::msg::Pose &pose, const double matching_distance) -> std::optional< double >
Definition: lanelet_map.cpp:25
auto noNextLaneletPoses() -> std::vector< std::pair< lanelet::Id, Pose >>
Calculates all poses on the map that have no next lanelet (dead ends)
Definition: lanelet_map.cpp:40
auto laneletLength(const lanelet::Id lanelet_id) -> double
Definition: lanelet_map.cpp:21
Definition: junit5.hpp:25