Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2_map_server::MapSaver Class Reference

A class that provides map saving methods and services. More...

#include <nav2_map_server/include/nav2_map_server/map_saver.hpp>

Inheritance diagram for nav2_map_server::MapSaver:
Inheritance graph
[legend]
Collaboration diagram for nav2_map_server::MapSaver:
Collaboration graph
[legend]

Public Member Functions

 MapSaver (const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 Constructor for the nav2_map_server::MapSaver. More...
 
 ~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. More...
 
nav2::CallbackReturn on_configure (const rclcpp_lifecycle::State &state) override
 Sets up map saving service. More...
 
nav2::CallbackReturn on_activate (const rclcpp_lifecycle::State &state) override
 Called when node switched to active state. More...
 
nav2::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &state) override
 Called when node switched to inactive state. More...
 
nav2::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &state) override
 Called when it is required node clean-up. More...
 
nav2::CallbackReturn on_shutdown (const rclcpp_lifecycle::State &state) override
 Called when in Shutdown state. More...
 
- Public Member Functions inherited from nav2::LifecycleNode
 LifecycleNode (const std::string &node_name, const std::string &ns, const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 A lifecycle node constructor. More...
 
 LifecycleNode (const std::string &node_name, const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 A lifecycle node constructor with no namespace. More...
 
template<typename ParamType >
ParamType declare_or_get_parameter (const std::string &parameter_name, const ParamType &default_value, const ParameterDescriptor &parameter_descriptor=ParameterDescriptor())
 Declares or gets a parameter. If the parameter is already declared, returns its value; otherwise declares it and returns the default value. More...
 
template<typename MessageT , typename CallbackT >
nav2::Subscription< MessageT >::SharedPtr create_subscription (const std::string &topic_name, CallbackT &&callback, const rclcpp::QoS &qos=nav2::qos::StandardTopicQoS(), const rclcpp::CallbackGroup::SharedPtr &callback_group=nullptr)
 Create a subscription to a topic using Nav2 QoS profiles and SubscriptionOptions. More...
 
template<typename MessageT >
nav2::Publisher< MessageT >::SharedPtr create_publisher (const std::string &topic_name, const rclcpp::QoS &qos=nav2::qos::StandardTopicQoS(), const rclcpp::CallbackGroup::SharedPtr &callback_group=nullptr)
 Create a publisher to a topic using Nav2 QoS profiles and PublisherOptions. More...
 
template<typename ServiceT >
nav2::ServiceClient< ServiceT >::SharedPtr create_client (const std::string &service_name, bool use_internal_executor=false)
 Create a ServiceClient to interface with a service. More...
 
template<typename ServiceT >
nav2::ServiceServer< ServiceT >::SharedPtr create_service (const std::string &service_name, typename nav2::ServiceServer< ServiceT >::CallbackType cb, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr)
 Create a ServiceServer to host with a service. More...
 
template<typename ActionT >
nav2::SimpleActionServer< ActionT >::SharedPtr create_action_server (const std::string &action_name, typename nav2::SimpleActionServer< ActionT >::ExecuteCallback execute_callback, typename nav2::SimpleActionServer< ActionT >::CompletionCallback compl_cb=nullptr, std::chrono::milliseconds server_timeout=std::chrono::milliseconds(500), bool spin_thread=false, const bool realtime=false)
 Create a SimpleActionServer to host with an action. More...
 
template<typename ActionT >
nav2::ActionClient< ActionT >::SharedPtr create_action_client (const std::string &action_name, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr)
 Create a ActionClient to call an action using. More...
 
nav2::LifecycleNode::SharedPtr shared_from_this ()
 Get a shared pointer of this.
 
nav2::LifecycleNode::WeakPtr weak_from_this ()
 Get a shared pointer of this.
 
nav2::CallbackReturn on_error (const rclcpp_lifecycle::State &)
 Abstracted on_error state transition callback, since unimplemented as of 2020 in the managed ROS2 node state machine. More...
 
void autostart ()
 Automatically configure and active the node.
 
virtual void on_rcl_preshutdown ()
 Perform preshutdown activities before our Context is shutdown. Note that this is related to our Context's shutdown sequence, not the lifecycle node state machine.
 
void createBond ()
 Create bond connection to lifecycle manager.
 
void destroyBond ()
 Destroy bond connection to lifecycle manager.
 

Protected Member 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. More...
 
- Protected Member Functions inherited from nav2::LifecycleNode
void printLifecycleNodeNotification ()
 Print notifications for lifecycle node.
 
void register_rcl_preshutdown_callback ()
 
void runCleanups ()
 

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"}
 
nav2::ServiceServer< nav2_msgs::srv::SaveMap >::SharedPtr save_map_service_
 
- Protected Attributes inherited from nav2::LifecycleNode
std::unique_ptr< rclcpp::PreShutdownCallbackHandle > rcl_preshutdown_cb_handle_ {nullptr}
 
std::shared_ptr< bond::Bond > bond_ {nullptr}
 
double bond_heartbeat_period {0.1}
 
rclcpp::TimerBase::SharedPtr autostart_timer_
 

Additional Inherited Members

- Public Types inherited from nav2::LifecycleNode
using SharedPtr = std::shared_ptr< nav2::LifecycleNode >
 
using WeakPtr = std::weak_ptr< nav2::LifecycleNode >
 
using SharedConstPointer = std::shared_ptr< const nav2::LifecycleNode >
 

Detailed Description

A class that provides map saving methods and services.

Definition at line 37 of file map_saver.hpp.

Constructor & Destructor Documentation

◆ MapSaver()

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

Constructor for the nav2_map_server::MapSaver.

Parameters
optionsAdditional options to control creation of the node.

Definition at line 44 of file map_saver.cpp.

Member Function Documentation

◆ on_activate()

nav2::CallbackReturn nav2_map_server::MapSaver::on_activate ( const rclcpp_lifecycle::State &  state)
override

Called when node switched to active state.

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 83 of file map_saver.cpp.

References nav2::LifecycleNode::createBond().

Here is the call graph for this function:

◆ on_cleanup()

nav2::CallbackReturn nav2_map_server::MapSaver::on_cleanup ( const rclcpp_lifecycle::State &  state)
override

Called when it is required node clean-up.

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 105 of file map_saver.cpp.

◆ on_configure()

nav2::CallbackReturn nav2_map_server::MapSaver::on_configure ( const rclcpp_lifecycle::State &  state)
override

Sets up map saving service.

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 61 of file map_saver.cpp.

References saveMapCallback().

Here is the call graph for this function:

◆ on_deactivate()

nav2::CallbackReturn nav2_map_server::MapSaver::on_deactivate ( const rclcpp_lifecycle::State &  state)
override

Called when node switched to inactive state.

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 94 of file map_saver.cpp.

References nav2::LifecycleNode::destroyBond().

Here is the call graph for this function:

◆ on_shutdown()

nav2::CallbackReturn nav2_map_server::MapSaver::on_shutdown ( const rclcpp_lifecycle::State &  state)
override

Called when in Shutdown state.

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 115 of file map_saver.cpp.

◆ saveMapCallback()

void nav2_map_server::MapSaver::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 
)
protected

Map saving service callback.

Parameters
request_headerService request header
requestService request
responseService response

Definition at line 121 of file map_saver.cpp.

Referenced by on_configure().

Here is the caller graph for this function:

◆ saveMapTopicToFile()

bool nav2_map_server::MapSaver::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_topicIncoming map topic name
save_parametersMap saving parameters.
Returns
true of false

Definition at line 144 of file map_saver.cpp.


The documentation for this class was generated from the following files: