Nav2 Navigation Stack - kilted  kilted
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_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::LifecycleNodeshared_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

nav2_util::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_util::CallbackReturn on_activate (const rclcpp_lifecycle::State &state) override
 Start publishing the map using the latched topic. More...
 
nav2_util::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &state) override
 Stops publishing the latched topic. More...
 
nav2_util::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &state) override
 Resets the member variables. More...
 
nav2_util::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_util::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_util::ServiceServer< nav_msgs::srv::GetMap, std::shared_ptr< nav2_util::LifecycleNode > >::SharedPtr occ_service_
 
nav2_util::ServiceServer< nav2_msgs::srv::LoadMap, std::shared_ptr< nav2_util::LifecycleNode > >::SharedPtr load_map_service_
 
rclcpp_lifecycle::LifecyclePublisher< nav_msgs::msg::OccupancyGrid >::SharedPtr occ_pub_
 
std::string frame_id_
 
nav_msgs::msg::OccupancyGrid msg_
 
bool map_available_
 
- 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_
 

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 184 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 200 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 221 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_util::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 133 of file map_server.cpp.

References nav2_util::LifecycleNode::createBond().

Here is the call graph for this function:

◆ on_cleanup()

nav2_util::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 164 of file map_server.cpp.

◆ on_configure()

nav2_util::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(), loadMapResponseFromYaml(), and nav2_util::LifecycleNode::shared_from_this().

Here is the call graph for this function:

◆ on_deactivate()

nav2_util::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 151 of file map_server.cpp.

References nav2_util::LifecycleNode::destroyBond().

Here is the call graph for this function:

◆ on_shutdown()

nav2_util::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 178 of file map_server.cpp.


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