19 #ifndef LANELET2_MAP_PROVIDER__LANELET2_MAP_PROVIDER_NODE_HPP_
20 #define LANELET2_MAP_PROVIDER__LANELET2_MAP_PROVIDER_NODE_HPP_
22 #include <rclcpp/rclcpp.hpp>
27 #include "autoware_auto_msgs/srv/had_map_service.hpp"
28 #include "autoware_auto_msgs/msg/had_map_bin.hpp"
58 std::shared_ptr<autoware_auto_msgs::srv::HADMapService_Request> request,
59 std::shared_ptr<autoware_auto_msgs::srv::HADMapService_Response> response);
68 std::unique_ptr<Lanelet2MapProvider> m_map_provider;
69 rclcpp::Service<autoware_auto_msgs::srv::HADMapService>::SharedPtr m_map_service;
76 #endif // LANELET2_MAP_PROVIDER__LANELET2_MAP_PROVIDER_NODE_HPP_