32 #include "nav2_map_server/map_saver.hpp"
40 using namespace std::placeholders;
42 namespace nav2_map_server
44 MapSaver::MapSaver(
const rclcpp::NodeOptions & options)
45 : nav2::LifecycleNode(
"map_saver",
"", options)
47 RCLCPP_INFO(get_logger(),
"Creating");
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);
63 RCLCPP_INFO(get_logger(),
"Configuring");
66 const std::string service_prefix = get_name() + std::string(
"/");
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();
75 save_map_service_ = create_service<nav2_msgs::srv::SaveMap>(
76 service_prefix + save_map_service_name_,
79 return nav2::CallbackReturn::SUCCESS;
85 RCLCPP_INFO(get_logger(),
"Activating");
90 return nav2::CallbackReturn::SUCCESS;
96 RCLCPP_INFO(get_logger(),
"Deactivating");
101 return nav2::CallbackReturn::SUCCESS;
107 RCLCPP_INFO(get_logger(),
"Cleaning up");
109 save_map_service_.reset();
111 return nav2::CallbackReturn::SUCCESS;
117 RCLCPP_INFO(get_logger(),
"Shutting down");
118 return nav2::CallbackReturn::SUCCESS;
122 const std::shared_ptr<rmw_request_id_t>,
123 const std::shared_ptr<nav2_msgs::srv::SaveMap::Request> request,
124 std::shared_ptr<nav2_msgs::srv::SaveMap::Response> response)
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;
133 save_parameters.mode = map_mode_from_string(request->map_mode);
134 }
catch (std::invalid_argument &) {
135 save_parameters.mode = MapMode::Trinary;
137 get_logger(),
"Map mode parameter not recognized: '%s', using default value (trinary)",
138 request->map_mode.c_str());
145 const std::string & map_topic,
149 std::string map_topic_loc = map_topic;
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());
158 if (map_topic_loc ==
"") {
159 map_topic_loc =
"map";
161 get_logger(),
"Map topic unspecified. Map messages will be read from \'%s\' topic",
162 map_topic_loc.c_str());
166 if (save_parameters_loc.free_thresh == 0.0) {
169 "Free threshold unspecified. Setting it to default value: %f",
170 free_thresh_default_);
171 save_parameters_loc.free_thresh = free_thresh_default_;
173 if (save_parameters_loc.occupied_thresh == 0.0) {
176 "Occupied threshold unspecified. Setting it to default value: %f",
177 occupied_thresh_default_);
178 save_parameters_loc.occupied_thresh = occupied_thresh_default_;
181 std::promise<nav_msgs::msg::OccupancyGrid::SharedPtr> prom;
182 std::future<nav_msgs::msg::OccupancyGrid::SharedPtr> future_result = prom.get_future();
184 auto mapCallback = [&prom](
185 const nav_msgs::msg::OccupancyGrid::SharedPtr msg) ->
void {
190 if (map_subscribe_transient_local_) {
195 auto callback_group = create_callback_group(
196 rclcpp::CallbackGroupType::MutuallyExclusive,
199 auto map_sub = create_subscription<nav_msgs::msg::OccupancyGrid>(
200 map_topic_loc, mapCallback, map_qos, callback_group);
203 rclcpp::executors::SingleThreadedExecutor executor;
204 executor.add_callback_group(callback_group, get_node_base_interface());
206 auto timeout = save_map_timeout_->to_chrono<std::chrono::nanoseconds>();
207 auto status = executor.spin_until_future_complete(future_result, timeout);
208 if (status != rclcpp::FutureReturnCode::SUCCESS) {
209 RCLCPP_ERROR(get_logger(),
"Failed to spin map subscription");
215 nav_msgs::msg::OccupancyGrid::SharedPtr map_msg = future_result.get();
216 if (saveMapToFile(*map_msg, save_parameters_loc)) {
217 RCLCPP_INFO(get_logger(),
"Map saved successfully");
220 RCLCPP_ERROR(get_logger(),
"Failed to save the map");
223 }
catch (std::exception & e) {
224 RCLCPP_ERROR(get_logger(),
"Failed to save the map: %s", e.what());
233 #include "rclcpp_components/register_node_macro.hpp"
void destroyBond()
Destroy bond connection to lifecycle manager.
void createBond()
Create bond connection to lifecycle manager.
A QoS profile for latched, reliable topics with a history of 10 messages.
A QoS profile for standard reliable topics with a history of 10 messages.
A class that provides map saving methods and services.
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Called when it is required node clean-up.
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Sets up map saving service.
~MapSaver()
Destructor for the nav2_map_server::MapServer.
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Called when node switched to active state.
nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in Shutdown 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::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Called when node switched to inactive state.