Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
nav2_lifecycle_manager::LifecycleManagerClient Class Reference
Collaboration diagram for nav2_lifecycle_manager::LifecycleManagerClient:
Collaboration graph
[legend]

Public Member Functions

 LifecycleManagerClient (const std::string &name, std::shared_ptr< rclcpp::Node > parent_node)
 A constructor for LifeCycleMangerClient. More...
 
bool startup (const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
 Make start up service call. More...
 
bool shutdown (const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
 Make shutdown service call. More...
 
bool pause (const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
 Make pause service call. More...
 
bool resume (const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
 Make resume service call. More...
 
bool reset (const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
 Make reset service call. More...
 
SystemStatus is_active (const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
 Check if lifecycle node manager server is active. More...
 

Protected Types

using ManageLifecycleNodes = nav2_msgs::srv::ManageLifecycleNodes
 

Protected Member Functions

bool callService (uint8_t command, const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
 A generic method used to call startup, shutdown, etc. More...
 

Protected Attributes

rclcpp::Node::SharedPtr node_
 
std::shared_ptr< nav2_util::ServiceClient< ManageLifecycleNodes > > manager_client_
 
std::shared_ptr< nav2_util::ServiceClient< std_srvs::srv::Trigger > > is_active_client_
 
std::string manage_service_name_
 
std::string active_service_name_
 

Detailed Description

Definition at line 43 of file lifecycle_manager_client.hpp.

Constructor & Destructor Documentation

◆ LifecycleManagerClient()

nav2_lifecycle_manager::LifecycleManagerClient::LifecycleManagerClient ( const std::string &  name,
std::shared_ptr< rclcpp::Node >  parent_node 
)
explicit

A constructor for LifeCycleMangerClient.

Parameters
nameManaged node name
parent_nodeNode that execute the service calls

Definition at line 29 of file lifecycle_manager_client.cpp.

Member Function Documentation

◆ callService()

bool nav2_lifecycle_manager::LifecycleManagerClient::callService ( uint8_t  command,
const std::chrono::nanoseconds  timeout = std::chrono::nanoseconds(-1) 
)
protected

A generic method used to call startup, shutdown, etc.

Parameters
command

Definition at line 108 of file lifecycle_manager_client.cpp.

Referenced by pause(), reset(), resume(), shutdown(), and startup().

Here is the caller graph for this function:

◆ is_active()

SystemStatus nav2_lifecycle_manager::LifecycleManagerClient::is_active ( const std::chrono::nanoseconds  timeout = std::chrono::nanoseconds(-1))

Check if lifecycle node manager server is active.

Returns
ACTIVE or INACTIVE or TIMEOUT

Definition at line 77 of file lifecycle_manager_client.cpp.

◆ pause()

bool nav2_lifecycle_manager::LifecycleManagerClient::pause ( const std::chrono::nanoseconds  timeout = std::chrono::nanoseconds(-1))

Make pause service call.

Returns
true or false

Definition at line 59 of file lifecycle_manager_client.cpp.

References callService().

Here is the call graph for this function:

◆ reset()

bool nav2_lifecycle_manager::LifecycleManagerClient::reset ( const std::chrono::nanoseconds  timeout = std::chrono::nanoseconds(-1))

Make reset service call.

Returns
true or false

Definition at line 71 of file lifecycle_manager_client.cpp.

References callService().

Here is the call graph for this function:

◆ resume()

bool nav2_lifecycle_manager::LifecycleManagerClient::resume ( const std::chrono::nanoseconds  timeout = std::chrono::nanoseconds(-1))

Make resume service call.

Returns
true or false

Definition at line 65 of file lifecycle_manager_client.cpp.

References callService().

Here is the call graph for this function:

◆ shutdown()

bool nav2_lifecycle_manager::LifecycleManagerClient::shutdown ( const std::chrono::nanoseconds  timeout = std::chrono::nanoseconds(-1))

Make shutdown service call.

Returns
true or false

Definition at line 53 of file lifecycle_manager_client.cpp.

References callService().

Here is the call graph for this function:

◆ startup()

bool nav2_lifecycle_manager::LifecycleManagerClient::startup ( const std::chrono::nanoseconds  timeout = std::chrono::nanoseconds(-1))

Make start up service call.

Returns
true or false

Definition at line 47 of file lifecycle_manager_client.cpp.

References callService().

Here is the call graph for this function:

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