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_util::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);
60 nav2_util::CallbackReturn
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();
76 std::shared_ptr<nav2_util::LifecycleNode>>>(
77 service_prefix + save_map_service_name_,
81 return nav2_util::CallbackReturn::SUCCESS;
84 nav2_util::CallbackReturn
87 RCLCPP_INFO(get_logger(),
"Activating");
92 return nav2_util::CallbackReturn::SUCCESS;
95 nav2_util::CallbackReturn
98 RCLCPP_INFO(get_logger(),
"Deactivating");
103 return nav2_util::CallbackReturn::SUCCESS;
106 nav2_util::CallbackReturn
109 RCLCPP_INFO(get_logger(),
"Cleaning up");
111 save_map_service_.reset();
113 return nav2_util::CallbackReturn::SUCCESS;
116 nav2_util::CallbackReturn
119 RCLCPP_INFO(get_logger(),
"Shutting down");
120 return nav2_util::CallbackReturn::SUCCESS;
124 const std::shared_ptr<rmw_request_id_t>,
125 const std::shared_ptr<nav2_msgs::srv::SaveMap::Request> request,
126 std::shared_ptr<nav2_msgs::srv::SaveMap::Response> response)
130 save_parameters.map_file_name = request->map_url;
131 save_parameters.image_format = request->image_format;
132 save_parameters.free_thresh = request->free_thresh;
133 save_parameters.occupied_thresh = request->occupied_thresh;
135 save_parameters.mode = map_mode_from_string(request->map_mode);
136 }
catch (std::invalid_argument &) {
137 save_parameters.mode = MapMode::Trinary;
139 get_logger(),
"Map mode parameter not recognized: '%s', using default value (trinary)",
140 request->map_mode.c_str());
147 const std::string & map_topic,
151 std::string map_topic_loc = map_topic;
155 get_logger(),
"Saving map from \'%s\' topic to \'%s\' file",
156 map_topic_loc.c_str(), save_parameters_loc.map_file_name.c_str());
160 if (map_topic_loc ==
"") {
161 map_topic_loc =
"map";
163 get_logger(),
"Map topic unspecified. Map messages will be read from \'%s\' topic",
164 map_topic_loc.c_str());
168 if (save_parameters_loc.free_thresh == 0.0) {
171 "Free threshold unspecified. Setting it to default value: %f",
172 free_thresh_default_);
173 save_parameters_loc.free_thresh = free_thresh_default_;
175 if (save_parameters_loc.occupied_thresh == 0.0) {
178 "Occupied threshold unspecified. Setting it to default value: %f",
179 occupied_thresh_default_);
180 save_parameters_loc.occupied_thresh = occupied_thresh_default_;
183 std::promise<nav_msgs::msg::OccupancyGrid::SharedPtr> prom;
184 std::future<nav_msgs::msg::OccupancyGrid::SharedPtr> future_result = prom.get_future();
186 auto mapCallback = [&prom](
187 const nav_msgs::msg::OccupancyGrid::SharedPtr msg) ->
void {
191 rclcpp::QoS map_qos(10);
192 if (map_subscribe_transient_local_) {
193 map_qos.transient_local();
195 map_qos.keep_last(1);
199 auto callback_group = create_callback_group(
200 rclcpp::CallbackGroupType::MutuallyExclusive,
203 auto option = rclcpp::SubscriptionOptions();
204 option.callback_group = callback_group;
205 auto map_sub = create_subscription<nav_msgs::msg::OccupancyGrid>(
206 map_topic_loc, map_qos, mapCallback, option);
209 rclcpp::executors::SingleThreadedExecutor executor;
210 executor.add_callback_group(callback_group, get_node_base_interface());
212 auto timeout = save_map_timeout_->to_chrono<std::chrono::nanoseconds>();
213 auto status = executor.spin_until_future_complete(future_result, timeout);
214 if (status != rclcpp::FutureReturnCode::SUCCESS) {
215 RCLCPP_ERROR(get_logger(),
"Failed to spin map subscription");
221 nav_msgs::msg::OccupancyGrid::SharedPtr map_msg = future_result.get();
222 if (saveMapToFile(*map_msg, save_parameters_loc)) {
223 RCLCPP_INFO(get_logger(),
"Map saved successfully");
226 RCLCPP_ERROR(get_logger(),
"Failed to save the map");
229 }
catch (std::exception & e) {
230 RCLCPP_ERROR(get_logger(),
"Failed to save the map: %s", e.what());
239 #include "rclcpp_components/register_node_macro.hpp"
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.
std::shared_ptr< nav2_util::LifecycleNode > shared_from_this()
Get a shared pointer of this.
void createBond()
Create bond connection to lifecycle manager.
void destroyBond()
Destroy bond connection to lifecycle manager.
A simple wrapper on ROS2 services server.