|
Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
A class that provides map saving methods and services. More...
#include <nav2_map_server/include/nav2_map_server/map_saver.hpp>


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_util::CallbackReturn | on_configure (const rclcpp_lifecycle::State &state) override |
| Sets up map saving service. More... | |
| nav2_util::CallbackReturn | on_activate (const rclcpp_lifecycle::State &state) override |
| Called when node switched to active state. More... | |
| nav2_util::CallbackReturn | on_deactivate (const rclcpp_lifecycle::State &state) override |
| Called when node switched to inactive state. More... | |
| nav2_util::CallbackReturn | on_cleanup (const rclcpp_lifecycle::State &state) override |
| Called when it is required node clean-up. More... | |
| nav2_util::CallbackReturn | on_shutdown (const rclcpp_lifecycle::State &state) override |
| Called when in Shutdown state. More... | |
Public Member Functions inherited from nav2_util::LifecycleNode | |
| LifecycleNode (const std::string &node_name, const std::string &ns="", const rclcpp::NodeOptions &options=rclcpp::NodeOptions()) | |
| A lifecycle node constructor. More... | |
| void | add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const std::string &description="", const std::string &additional_constraints="", bool read_only=false) |
| Declare a parameter that has no integer or floating point range constraints. More... | |
| void | add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const floating_point_range fp_range, const std::string &description="", const std::string &additional_constraints="", bool read_only=false) |
| Declare a parameter that has a floating point range constraint. More... | |
| void | add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const integer_range int_range, const std::string &description="", const std::string &additional_constraints="", bool read_only=false) |
| Declare a parameter that has an integer range constraint. More... | |
| std::shared_ptr< nav2_util::LifecycleNode > | shared_from_this () |
| Get a shared pointer of this. | |
| nav2_util::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_util::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_util::ServiceServer< nav2_msgs::srv::SaveMap, std::shared_ptr< nav2_util::LifecycleNode > >::SharedPtr | save_map_service_ |
Protected Attributes inherited from nav2_util::LifecycleNode | |
| std::unique_ptr< rclcpp::PreShutdownCallbackHandle > | rcl_preshutdown_cb_handle_ {nullptr} |
| std::shared_ptr< bond::Bond > | bond_ {nullptr} |
| double | bond_heartbeat_period |
| rclcpp::TimerBase::SharedPtr | autostart_timer_ |
A class that provides map saving methods and services.
Definition at line 37 of file map_saver.hpp.
|
explicit |
Constructor for the nav2_map_server::MapSaver.
| options | Additional options to control creation of the node. |
Definition at line 44 of file map_saver.cpp.
|
override |
Called when node switched to active state.
| state | Lifecycle Node's state |
Definition at line 85 of file map_saver.cpp.
References nav2_util::LifecycleNode::createBond().

|
override |
Called when it is required node clean-up.
| state | Lifecycle Node's state |
Definition at line 107 of file map_saver.cpp.
|
override |
Sets up map saving service.
| state | Lifecycle Node's state |
Definition at line 61 of file map_saver.cpp.
References saveMapCallback(), and nav2_util::LifecycleNode::shared_from_this().

|
override |
Called when node switched to inactive state.
| state | Lifecycle Node's state |
Definition at line 96 of file map_saver.cpp.
References nav2_util::LifecycleNode::destroyBond().

|
override |
Called when in Shutdown state.
| state | Lifecycle Node's state |
Definition at line 117 of file map_saver.cpp.
|
protected |
Map saving service callback.
| request_header | Service request header |
| request | Service request |
| response | Service response |
Definition at line 123 of file map_saver.cpp.
Referenced by on_configure().

| 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.
| map_topic | Incoming map topic name |
| save_parameters | Map saving parameters. |
Definition at line 146 of file map_saver.cpp.