Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
map_saver.cpp
1 /*
2  * Copyright (c) 2020 Samsung Research Russia
3  * Copyright 2019 Rover Robotics
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright
11  * notice, this list of conditions and the following disclaimer.
12  * * Redistributions in binary form must reproduce the above copyright
13  * notice, this list of conditions and the following disclaimer in the
14  * documentation and/or other materials provided with the distribution.
15  * * Neither the name of the <ORGANIZATION> nor the names of its
16  * contributors may be used to endorse or promote products derived from
17  * this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #include "nav2_map_server/map_saver.hpp"
33 
34 #include <string>
35 #include <memory>
36 #include <stdexcept>
37 #include <functional>
38 #include <mutex>
39 
40 using namespace std::placeholders;
41 
42 namespace nav2_map_server
43 {
44 MapSaver::MapSaver(const rclcpp::NodeOptions & options)
45 : nav2_util::LifecycleNode("map_saver", "", options)
46 {
47  RCLCPP_INFO(get_logger(), "Creating");
48 
49  // Declare the node parameters
50  declare_parameter("save_map_timeout", 2.0);
51  declare_parameter("free_thresh_default", 0.25);
52  declare_parameter("occupied_thresh_default", 0.65);
53  declare_parameter("map_subscribe_transient_local", true);
54 }
55 
57 {
58 }
59 
60 nav2_util::CallbackReturn
61 MapSaver::on_configure(const rclcpp_lifecycle::State & /*state*/)
62 {
63  RCLCPP_INFO(get_logger(), "Configuring");
64 
65  // Make name prefix for services
66  const std::string service_prefix = get_name() + std::string("/");
67 
68  save_map_timeout_ = std::make_shared<rclcpp::Duration>(
69  rclcpp::Duration::from_seconds(get_parameter("save_map_timeout").as_double()));
70  free_thresh_default_ = get_parameter("free_thresh_default").as_double();
71  occupied_thresh_default_ = get_parameter("occupied_thresh_default").as_double();
72  map_subscribe_transient_local_ = get_parameter("map_subscribe_transient_local").as_bool();
73 
74  // Create a service that saves the occupancy grid from map topic to a file
75  save_map_service_ = create_service<nav2_msgs::srv::SaveMap>(
76  service_prefix + save_map_service_name_,
77  std::bind(&MapSaver::saveMapCallback, this, _1, _2, _3));
78 
79  return nav2_util::CallbackReturn::SUCCESS;
80 }
81 
82 nav2_util::CallbackReturn
83 MapSaver::on_activate(const rclcpp_lifecycle::State & /*state*/)
84 {
85  RCLCPP_INFO(get_logger(), "Activating");
86 
87  // create bond connection
88  createBond();
89 
90  return nav2_util::CallbackReturn::SUCCESS;
91 }
92 
93 nav2_util::CallbackReturn
94 MapSaver::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
95 {
96  RCLCPP_INFO(get_logger(), "Deactivating");
97 
98  // destroy bond connection
99  destroyBond();
100 
101  return nav2_util::CallbackReturn::SUCCESS;
102 }
103 
104 nav2_util::CallbackReturn
105 MapSaver::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
106 {
107  RCLCPP_INFO(get_logger(), "Cleaning up");
108 
109  save_map_service_.reset();
110 
111  return nav2_util::CallbackReturn::SUCCESS;
112 }
113 
114 nav2_util::CallbackReturn
115 MapSaver::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
116 {
117  RCLCPP_INFO(get_logger(), "Shutting down");
118  return nav2_util::CallbackReturn::SUCCESS;
119 }
120 
122  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
123  const std::shared_ptr<nav2_msgs::srv::SaveMap::Request> request,
124  std::shared_ptr<nav2_msgs::srv::SaveMap::Response> response)
125 {
126  // Set input arguments and call saveMapTopicToFile()
127  SaveParameters save_parameters;
128  save_parameters.map_file_name = request->map_url;
129  save_parameters.image_format = request->image_format;
130  save_parameters.free_thresh = request->free_thresh;
131  save_parameters.occupied_thresh = request->occupied_thresh;
132  try {
133  save_parameters.mode = map_mode_from_string(request->map_mode);
134  } catch (std::invalid_argument &) {
135  save_parameters.mode = MapMode::Trinary;
136  RCLCPP_WARN(
137  get_logger(), "Map mode parameter not recognized: '%s', using default value (trinary)",
138  request->map_mode.c_str());
139  }
140 
141  response->result = saveMapTopicToFile(request->map_topic, save_parameters);
142 }
143 
145  const std::string & map_topic,
146  const SaveParameters & save_parameters)
147 {
148  // Local copies of map_topic and save_parameters that could be changed
149  std::string map_topic_loc = map_topic;
150  SaveParameters save_parameters_loc = save_parameters;
151 
152  RCLCPP_INFO(
153  get_logger(), "Saving map from \'%s\' topic to \'%s\' file",
154  map_topic_loc.c_str(), save_parameters_loc.map_file_name.c_str());
155 
156  try {
157  // Correct map_topic_loc if necessary
158  if (map_topic_loc == "") {
159  map_topic_loc = "map";
160  RCLCPP_WARN(
161  get_logger(), "Map topic unspecified. Map messages will be read from \'%s\' topic",
162  map_topic_loc.c_str());
163  }
164 
165  // Set default for MapSaver node thresholds parameters
166  if (save_parameters_loc.free_thresh == 0.0) {
167  RCLCPP_WARN(
168  get_logger(),
169  "Free threshold unspecified. Setting it to default value: %f",
170  free_thresh_default_);
171  save_parameters_loc.free_thresh = free_thresh_default_;
172  }
173  if (save_parameters_loc.occupied_thresh == 0.0) {
174  RCLCPP_WARN(
175  get_logger(),
176  "Occupied threshold unspecified. Setting it to default value: %f",
177  occupied_thresh_default_);
178  save_parameters_loc.occupied_thresh = occupied_thresh_default_;
179  }
180 
181  std::promise<nav_msgs::msg::OccupancyGrid::SharedPtr> prom;
182  std::future<nav_msgs::msg::OccupancyGrid::SharedPtr> future_result = prom.get_future();
183  // A callback function that receives map message from subscribed topic
184  auto mapCallback = [&prom](
185  const nav_msgs::msg::OccupancyGrid::SharedPtr msg) -> void {
186  prom.set_value(msg);
187  };
188 
189  rclcpp::QoS map_qos(10); // initialize to default
190  if (map_subscribe_transient_local_) {
191  map_qos.transient_local();
192  map_qos.reliable();
193  map_qos.keep_last(1);
194  }
195 
196  // Create new CallbackGroup for map_sub
197  auto callback_group = create_callback_group(
198  rclcpp::CallbackGroupType::MutuallyExclusive,
199  false);
200 
201  auto option = rclcpp::SubscriptionOptions();
202  option.callback_group = callback_group;
203  auto map_sub = create_subscription<nav_msgs::msg::OccupancyGrid>(
204  map_topic_loc, map_qos, mapCallback, option);
205 
206  // Create SingleThreadedExecutor to spin map_sub in callback_group
207  rclcpp::executors::SingleThreadedExecutor executor;
208  executor.add_callback_group(callback_group, get_node_base_interface());
209  // Spin until map message received
210  auto timeout = save_map_timeout_->to_chrono<std::chrono::nanoseconds>();
211  auto status = executor.spin_until_future_complete(future_result, timeout);
212  if (status != rclcpp::FutureReturnCode::SUCCESS) {
213  RCLCPP_ERROR(get_logger(), "Failed to spin map subscription");
214  return false;
215  }
216  // map_sub is no more needed
217  map_sub.reset();
218  // Map message received. Saving it to file
219  nav_msgs::msg::OccupancyGrid::SharedPtr map_msg = future_result.get();
220  if (saveMapToFile(*map_msg, save_parameters_loc)) {
221  RCLCPP_INFO(get_logger(), "Map saved successfully");
222  return true;
223  } else {
224  RCLCPP_ERROR(get_logger(), "Failed to save the map");
225  return false;
226  }
227  } catch (std::exception & e) {
228  RCLCPP_ERROR(get_logger(), "Failed to save the map: %s", e.what());
229  return false;
230  }
231 
232  return false;
233 }
234 
235 } // namespace nav2_map_server
236 
237 #include "rclcpp_components/register_node_macro.hpp"
238 
239 // Register the component with class_loader.
240 // This acts as a sort of entry point, allowing the component to be discoverable when its library
241 // is being loaded into a running process.
242 RCLCPP_COMPONENTS_REGISTER_NODE(nav2_map_server::MapSaver)
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
void createBond()
Create bond connection to lifecycle manager.
void destroyBond()
Destroy bond connection to lifecycle manager.