16 #ifndef NAV2_MAP_SERVER__MAP_SAVER_HPP_
17 #define NAV2_MAP_SERVER__MAP_SAVER_HPP_
22 #include "rclcpp/rclcpp.hpp"
23 #include "nav2_util/lifecycle_node.hpp"
24 #include "nav2_msgs/srv/save_map.hpp"
28 namespace nav2_map_server
42 explicit MapSaver(
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
56 const std::string & map_topic,
64 nav2_util::CallbackReturn
on_configure(
const rclcpp_lifecycle::State & state)
override;
70 nav2_util::CallbackReturn
on_activate(
const rclcpp_lifecycle::State & state)
override;
76 nav2_util::CallbackReturn
on_deactivate(
const rclcpp_lifecycle::State & state)
override;
82 nav2_util::CallbackReturn
on_cleanup(
const rclcpp_lifecycle::State & state)
override;
88 nav2_util::CallbackReturn
on_shutdown(
const rclcpp_lifecycle::State & state)
override;
98 const std::shared_ptr<rmw_request_id_t> request_header,
99 const std::shared_ptr<nav2_msgs::srv::SaveMap::Request> request,
100 std::shared_ptr<nav2_msgs::srv::SaveMap::Response> response);
103 std::shared_ptr<rclcpp::Duration> save_map_timeout_;
105 double free_thresh_default_;
106 double occupied_thresh_default_;
108 bool map_subscribe_transient_local_;
111 const std::string save_map_service_name_{
"save_map"};
113 rclcpp::Service<nav2_msgs::srv::SaveMap>::SharedPtr save_map_service_;
A class that provides map saving methods and services.
~MapSaver()
Destructor for the nav2_map_server::MapServer.
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Called when node switched to active state.
void saveMapCallback(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< nav2_msgs::srv::SaveMap::Request > request, std::shared_ptr< nav2_msgs::srv::SaveMap::Response > response)
Map saving service callback.
bool saveMapTopicToFile(const std::string &map_topic, const SaveParameters &save_parameters)
Read a message from incoming map topic and save map to a file.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Called when node switched to inactive state.
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Called when it is required node clean-up.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Sets up map saving service.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in Shutdown state.
MapSaver(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor for the nav2_map_server::MapSaver.
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.