Class MapSaver

Inheritance Relationships

Base Type

  • public nav2_util::LifecycleNode

Class Documentation

class MapSaver : public nav2_util::LifecycleNode

A class that provides map saving methods and services.

Public Functions

explicit MapSaver(const rclcpp::NodeOptions &options = rclcpp::NodeOptions())

Constructor for the nav2_map_server::MapSaver.

Parameters:

options – Additional options to control creation of the node.

~MapSaver()

Destructor for the nav2_map_server::MapServer.

bool saveMapTopicToFile(const std::string &map_topic, const SaveParameters &save_parameters)

Read a message from incoming map topic and save map to a file.

Parameters:
  • map_topic – Incoming map topic name

  • save_parameters – Map saving parameters.

Returns:

true of false

nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override

Sets up map saving service.

Parameters:

state – Lifecycle Node’s state

Returns:

Success or Failure

nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override

Called when node switched to active state.

Parameters:

state – Lifecycle Node’s state

Returns:

Success or Failure

nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override

Called when node switched to inactive state.

Parameters:

state – Lifecycle Node’s state

Returns:

Success or Failure

nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override

Called when it is required node clean-up.

Parameters:

state – Lifecycle Node’s state

Returns:

Success or Failure

nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override

Called when in Shutdown state.

Parameters:

state – Lifecycle Node’s state

Returns:

Success or Failure

Protected Functions

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.

Parameters:
  • request_header – Service request header

  • request – Service request

  • response – Service response

Protected Attributes

std::shared_ptr<rclcpp::Duration> save_map_timeout_
double free_thresh_default_
double occupied_thresh_default_
bool map_subscribe_transient_local_
const std::string save_map_service_name_ = {"save_map"}
rclcpp::Service<nav2_msgs::srv::SaveMap>::SharedPtr save_map_service_