Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
map_saver.hpp
1 // Copyright (c) 2020 Samsung Research Russia
2 // Copyright (c) 2018 Intel Corporation
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #ifndef NAV2_MAP_SERVER__MAP_SAVER_HPP_
17 #define NAV2_MAP_SERVER__MAP_SAVER_HPP_
18 
19 #include <string>
20 #include <memory>
21 
22 #include "rclcpp/rclcpp.hpp"
23 #include "nav2_util/lifecycle_node.hpp"
24 #include "nav2_msgs/srv/save_map.hpp"
25 
26 #include "map_io.hpp"
27 
28 namespace nav2_map_server
29 {
30 
36 {
37 public:
42  explicit MapSaver(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
43 
47  ~MapSaver();
48 
55  bool saveMapTopicToFile(
56  const std::string & map_topic,
57  const SaveParameters & save_parameters);
58 
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;
89 
90 protected:
97  void saveMapCallback(
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);
101 
102  // The timeout for saving the map in service
103  std::shared_ptr<rclcpp::Duration> save_map_timeout_;
104  // Default values for map thresholds
105  double free_thresh_default_;
106  double occupied_thresh_default_;
107  // param for handling QoS configuration
108  bool map_subscribe_transient_local_;
109 
110  // The name of the service for saving a map from topic
111  const std::string save_map_service_name_{"save_map"};
112  // A service to save the map to a file at run time (SaveMap)
113  rclcpp::Service<nav2_msgs::srv::SaveMap>::SharedPtr save_map_service_;
114 };
115 
116 } // namespace nav2_map_server
117 
118 #endif // NAV2_MAP_SERVER__MAP_SAVER_HPP_
A class that provides map saving methods and services.
Definition: map_saver.hpp:36
~MapSaver()
Destructor for the nav2_map_server::MapServer.
Definition: map_saver.cpp:56
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Called when node switched to active state.
Definition: map_saver.cpp:83
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.
Definition: map_saver.cpp:121
bool saveMapTopicToFile(const std::string &map_topic, const SaveParameters &save_parameters)
Read a message from incoming map topic and save map to a file.
Definition: map_saver.cpp:144
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Called when node switched to inactive state.
Definition: map_saver.cpp:94
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Called when it is required node clean-up.
Definition: map_saver.cpp:105
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Sets up map saving service.
Definition: map_saver.cpp:61
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in Shutdown state.
Definition: map_saver.cpp:115
MapSaver(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor for the nav2_map_server::MapSaver.
Definition: map_saver.cpp:44
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.