15 #ifndef HAD_MAP_UTILS__HAD_MAP_CONVERSION_HPP_ 16 #define HAD_MAP_UTILS__HAD_MAP_CONVERSION_HPP_ 18 #include <autoware_auto_msgs/msg/had_map_bin.hpp> 27 namespace had_map_utils
31 const std::shared_ptr<lanelet::LaneletMap> & map,
32 autoware_auto_msgs::msg::HADMapBin & msg);
35 const autoware_auto_msgs::msg::HADMapBin & msg,
36 std::shared_ptr<lanelet::LaneletMap> & map);
42 #endif // HAD_MAP_UTILS__HAD_MAP_CONVERSION_HPP_ void HAD_MAP_UTILS_PUBLIC toBinaryMsg(const std::shared_ptr< lanelet::LaneletMap > &map, autoware_auto_msgs::msg::HADMapBin &msg)
Definition: had_map_conversion.cpp:40
void HAD_MAP_UTILS_PUBLIC fromBinaryMsg(const autoware_auto_msgs::msg::HADMapBin &msg, std::shared_ptr< lanelet::LaneletMap > &map)
Definition: had_map_conversion.cpp:56
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24