15 #ifndef NAV2_MAP_SERVER__MAP_SERVER_HPP_
16 #define NAV2_MAP_SERVER__MAP_SERVER_HPP_
21 #include "nav2_ros_common/lifecycle_node.hpp"
22 #include "nav2_ros_common/service_server.hpp"
23 #include "nav_msgs/msg/occupancy_grid.hpp"
24 #include "nav_msgs/srv/get_map.hpp"
25 #include "nav2_msgs/srv/load_map.hpp"
26 #include "rclcpp/rclcpp.hpp"
27 #include "rclcpp_lifecycle/state.hpp"
29 namespace nav2_map_server
44 explicit MapServer(
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
57 nav2::CallbackReturn
on_configure(
const rclcpp_lifecycle::State & state)
override;
63 nav2::CallbackReturn
on_activate(
const rclcpp_lifecycle::State & state)
override;
69 nav2::CallbackReturn
on_deactivate(
const rclcpp_lifecycle::State & state)
override;
75 nav2::CallbackReturn
on_cleanup(
const rclcpp_lifecycle::State & state)
override;
81 nav2::CallbackReturn
on_shutdown(
const rclcpp_lifecycle::State & state)
override;
92 const std::string & yaml_file,
93 std::shared_ptr<nav2_msgs::srv::LoadMap::Response> response);
107 const std::shared_ptr<rmw_request_id_t> request_header,
108 const std::shared_ptr<nav_msgs::srv::GetMap::Request> request,
109 std::shared_ptr<nav_msgs::srv::GetMap::Response> response);
118 const std::shared_ptr<rmw_request_id_t> request_header,
119 const std::shared_ptr<nav2_msgs::srv::LoadMap::Request> request,
120 std::shared_ptr<nav2_msgs::srv::LoadMap::Response> response);
123 const std::string service_name_{
"map"};
126 const std::string load_map_service_name_{
"load_map"};
129 nav2::ServiceServer<nav_msgs::srv::GetMap>::SharedPtr occ_service_;
132 nav2::ServiceServer<nav2_msgs::srv::LoadMap>::SharedPtr load_map_service_;
135 nav2::Publisher<nav_msgs::msg::OccupancyGrid>::SharedPtr occ_pub_;
138 std::string frame_id_;
141 nav_msgs::msg::OccupancyGrid msg_;
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
Parses the map yaml file and creates a service and a publisher that provides occupancy grid.
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Start publishing the map using the latched topic.
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.
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::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in Shutdown state.
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Sets up required params and services. Loads map and its parameters from the file.
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Stops publishing the latched topic.
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Resets the member variables.