Nav2 Navigation Stack - jazzy
jazzy
ROS 2 Navigation Stack
|
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>
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. | |
![]() | |
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 | |
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... | |
![]() | |
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"} |
rclcpp::Service< nav_msgs::srv::GetMap >::SharedPtr | occ_service_ |
rclcpp::Service< nav2_msgs::srv::LoadMap >::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_ |
![]() | |
std::unique_ptr< rclcpp::PreShutdownCallbackHandle > | rcl_preshutdown_cb_handle_ {nullptr} |
std::unique_ptr< bond::Bond > | bond_ {nullptr} |
double | bond_heartbeat_period |
rclcpp::TimerBase::SharedPtr | autostart_timer_ |
Parses the map yaml file and creates a service and a publisher that provides occupancy grid.
Definition at line 36 of file map_server.hpp.
|
explicit |
A constructor for nav2_map_server::MapServer.
options | Additional options to control creation of the node. |
Definition at line 65 of file map_server.cpp.
|
protected |
Map getting service callback.
request_header | Service request header |
request | Service request |
response | Service response |
Definition at line 180 of file map_server.cpp.
Referenced by on_configure().
|
protected |
Map loading service callback.
request_header | Service request header |
request | Service request |
response | Service response |
Definition at line 196 of file map_server.cpp.
References loadMapResponseFromYaml().
Referenced by on_configure().
|
protected |
Load the map YAML, image from map file name and generate output response containing an OccupancyGrid. Update msg_ class variable.
yaml_file | name of input YAML file |
response | Output response with loaded OccupancyGrid map |
Definition at line 217 of file map_server.cpp.
References updateMsgHeader().
Referenced by loadMapCallback(), and on_configure().
|
overrideprotected |
Start publishing the map using the latched topic.
state | Lifecycle Node's state |
Definition at line 129 of file map_server.cpp.
References nav2_util::LifecycleNode::createBond().
|
overrideprotected |
Resets the member variables.
state | Lifecycle Node's state |
Definition at line 160 of file map_server.cpp.
|
overrideprotected |
Sets up required params and services. Loads map and its parameters from the file.
state | Lifecycle Node's state |
Definition at line 81 of file map_server.cpp.
References getMapCallback(), loadMapCallback(), and loadMapResponseFromYaml().
|
overrideprotected |
Stops publishing the latched topic.
state | Lifecycle Node's state |
Definition at line 147 of file map_server.cpp.
References nav2_util::LifecycleNode::destroyBond().
|
overrideprotected |
Called when in Shutdown state.
state | Lifecycle Node's state |
Definition at line 174 of file map_server.cpp.