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

Parses the map yaml file and creates a service and a publisher that provides occupancy grid. More...

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

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

Public Member Functions

 MapServer (const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 A constructor for nav2_map_server::MapServer. More...
 
 ~MapServer ()
 A Destructor for nav2_map_server::MapServer.
 
- 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

nav2::CallbackReturn on_configure (const rclcpp_lifecycle::State &state) override
 Sets up required params and services. Loads map and its parameters from the file. More...
 
nav2::CallbackReturn on_activate (const rclcpp_lifecycle::State &state) override
 Start publishing the map using the latched topic. More...
 
nav2::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &state) override
 Stops publishing the latched topic. More...
 
nav2::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &state) override
 Resets the member variables. More...
 
nav2::CallbackReturn on_shutdown (const rclcpp_lifecycle::State &state) override
 Called when in Shutdown state. More...
 
bool loadMapResponseFromYaml (const std::string &yaml_file, std::shared_ptr< nav2_msgs::srv::LoadMap::Response > response)
 Load the map YAML, image from map file name and generate output response containing an OccupancyGrid. Update msg_ class variable. More...
 
void updateMsgHeader ()
 Method correcting msg_ header when it belongs to instantiated object.
 
void getMapCallback (const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< nav_msgs::srv::GetMap::Request > request, std::shared_ptr< nav_msgs::srv::GetMap::Response > response)
 Map getting service callback. More...
 
void loadMapCallback (const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< nav2_msgs::srv::LoadMap::Request > request, std::shared_ptr< nav2_msgs::srv::LoadMap::Response > response)
 Map loading 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

const std::string service_name_ {"map"}
 
const std::string load_map_service_name_ {"load_map"}
 
nav2::ServiceServer< nav_msgs::srv::GetMap >::SharedPtr occ_service_
 
nav2::ServiceServer< nav2_msgs::srv::LoadMap >::SharedPtr load_map_service_
 
nav2::Publisher< nav_msgs::msg::OccupancyGrid >::SharedPtr occ_pub_
 
std::string frame_id_
 
nav_msgs::msg::OccupancyGrid msg_
 
bool map_available_
 
- 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

Parses the map yaml file and creates a service and a publisher that provides occupancy grid.

Definition at line 37 of file map_server.hpp.

Constructor & Destructor Documentation

◆ MapServer()

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

A constructor for nav2_map_server::MapServer.

Parameters
optionsAdditional options to control creation of the node.

Definition at line 65 of file map_server.cpp.

Member Function Documentation

◆ getMapCallback()

void nav2_map_server::MapServer::getMapCallback ( const std::shared_ptr< rmw_request_id_t >  request_header,
const std::shared_ptr< nav_msgs::srv::GetMap::Request >  request,
std::shared_ptr< nav_msgs::srv::GetMap::Response >  response 
)
protected

Map getting service callback.

Parameters
request_headerService request header
requestService request
responseService response

Definition at line 180 of file map_server.cpp.

Referenced by on_configure().

Here is the caller graph for this function:

◆ loadMapCallback()

void nav2_map_server::MapServer::loadMapCallback ( const std::shared_ptr< rmw_request_id_t >  request_header,
const std::shared_ptr< nav2_msgs::srv::LoadMap::Request >  request,
std::shared_ptr< nav2_msgs::srv::LoadMap::Response >  response 
)
protected

Map loading service callback.

Parameters
request_headerService request header
requestService request
responseService response

Definition at line 196 of file map_server.cpp.

References loadMapResponseFromYaml().

Referenced by on_configure().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ loadMapResponseFromYaml()

bool nav2_map_server::MapServer::loadMapResponseFromYaml ( const std::string &  yaml_file,
std::shared_ptr< nav2_msgs::srv::LoadMap::Response >  response 
)
protected

Load the map YAML, image from map file name and generate output response containing an OccupancyGrid. Update msg_ class variable.

Parameters
yaml_filename of input YAML file
responseOutput response with loaded OccupancyGrid map
Returns
true or false

Definition at line 217 of file map_server.cpp.

References updateMsgHeader().

Referenced by loadMapCallback(), and on_configure().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ on_activate()

nav2::CallbackReturn nav2_map_server::MapServer::on_activate ( const rclcpp_lifecycle::State &  state)
overrideprotected

Start publishing the map using the latched topic.

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 129 of file map_server.cpp.

References nav2::LifecycleNode::createBond().

Here is the call graph for this function:

◆ on_cleanup()

nav2::CallbackReturn nav2_map_server::MapServer::on_cleanup ( const rclcpp_lifecycle::State &  state)
overrideprotected

Resets the member variables.

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 160 of file map_server.cpp.

◆ on_configure()

nav2::CallbackReturn nav2_map_server::MapServer::on_configure ( const rclcpp_lifecycle::State &  state)
overrideprotected

Sets up required params and services. Loads map and its parameters from the file.

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 81 of file map_server.cpp.

References getMapCallback(), loadMapCallback(), and loadMapResponseFromYaml().

Here is the call graph for this function:

◆ on_deactivate()

nav2::CallbackReturn nav2_map_server::MapServer::on_deactivate ( const rclcpp_lifecycle::State &  state)
overrideprotected

Stops publishing the latched topic.

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 147 of file map_server.cpp.

References nav2::LifecycleNode::destroyBond().

Here is the call graph for this function:

◆ on_shutdown()

nav2::CallbackReturn nav2_map_server::MapServer::on_shutdown ( const rclcpp_lifecycle::State &  state)
overrideprotected

Called when in Shutdown state.

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 174 of file map_server.cpp.


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