15 #ifndef NAV2_MAP_SERVER__MAP_SERVER_HPP_
16 #define NAV2_MAP_SERVER__MAP_SERVER_HPP_
22 #include "rclcpp/rclcpp.hpp"
23 #include "nav2_util/lifecycle_node.hpp"
24 #include "nav_msgs/msg/occupancy_grid.hpp"
25 #include "nav_msgs/srv/get_map.hpp"
26 #include "nav2_msgs/srv/load_map.hpp"
28 namespace nav2_map_server
43 explicit MapServer(
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
56 nav2_util::CallbackReturn
on_configure(
const rclcpp_lifecycle::State & state)
override;
62 nav2_util::CallbackReturn
on_activate(
const rclcpp_lifecycle::State & state)
override;
68 nav2_util::CallbackReturn
on_deactivate(
const rclcpp_lifecycle::State & state)
override;
74 nav2_util::CallbackReturn
on_cleanup(
const rclcpp_lifecycle::State & state)
override;
80 nav2_util::CallbackReturn
on_shutdown(
const rclcpp_lifecycle::State & state)
override;
91 const std::string & yaml_file,
92 std::shared_ptr<nav2_msgs::srv::LoadMap::Response> response);
106 const std::shared_ptr<rmw_request_id_t> request_header,
107 const std::shared_ptr<nav_msgs::srv::GetMap::Request> request,
108 std::shared_ptr<nav_msgs::srv::GetMap::Response> response);
117 const std::shared_ptr<rmw_request_id_t> request_header,
118 const std::shared_ptr<nav2_msgs::srv::LoadMap::Request> request,
119 std::shared_ptr<nav2_msgs::srv::LoadMap::Response> response);
122 const std::string service_name_{
"map"};
125 const std::string load_map_service_name_{
"load_map"};
128 rclcpp::Service<nav_msgs::srv::GetMap>::SharedPtr occ_service_;
131 rclcpp::Service<nav2_msgs::srv::LoadMap>::SharedPtr load_map_service_;
134 rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::OccupancyGrid>::SharedPtr occ_pub_;
137 std::string frame_id_;
140 nav_msgs::msg::OccupancyGrid msg_;
Parses the map yaml file and creates a service and a publisher that provides occupancy grid.
void loadMapCallback(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< nav2_msgs::srv::LoadMap::Request > request, std::shared_ptr< nav2_msgs::srv::LoadMap::Response > response)
Map loading service callback.
void getMapCallback(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< nav_msgs::srv::GetMap::Request > request, std::shared_ptr< nav_msgs::srv::GetMap::Response > response)
Map getting service callback.
void updateMsgHeader()
Method correcting msg_ header when it belongs to instantiated object.
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Start publishing the map using the latched topic.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in Shutdown state.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Stops publishing the latched topic.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Sets up required params and services. Loads map and its parameters from the file.
MapServer(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
A constructor for nav2_map_server::MapServer.
~MapServer()
A Destructor for nav2_map_server::MapServer.
bool loadMapResponseFromYaml(const std::string &yaml_file, std::shared_ptr< nav2_msgs::srv::LoadMap::Response > response)
Load the map YAML, image from map file name and generate output response containing an OccupancyGrid....
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Resets the member variables.
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.