14 #ifndef TRAFFIC_SIMULATOR__LANELET_LOADER_HPP_
15 #define TRAFFIC_SIMULATOR__LANELET_LOADER_HPP_
17 #include <lanelet2_io/Io.h>
19 #include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
24 namespace lanelet_wrapper
29 static auto load(
const std::filesystem::path & lanelet_map_path) -> lanelet::LaneletMapPtr;
30 static auto convertMapToBin(
const lanelet::LaneletMapPtr lanelet_map_ptr)
31 -> autoware_map_msgs::msg::LaneletMapBin;
34 static auto overwriteLaneletsCenterline(lanelet::LaneletMapPtr) -> void;
35 static auto resamplePoints(
36 const lanelet::ConstLineString3d & line_string,
const std::int32_t num_segments)
37 -> lanelet::BasicPoints3d;
38 static auto calculateAccumulatedLengths(
const lanelet::ConstLineString3d & line_string)
39 -> std::vector<double>;
Definition: lanelet_loader.hpp:27
static auto load(const std::filesystem::path &lanelet_map_path) -> lanelet::LaneletMapPtr
Definition: lanelet_loader.cpp:56
static auto convertMapToBin(const lanelet::LaneletMapPtr lanelet_map_ptr) -> autoware_map_msgs::msg::LaneletMapBin
Definition: lanelet_loader.cpp:120