|
Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|

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_ |
Definition at line 43 of file lifecycle_manager_client.hpp.
|
explicit |
A constructor for LifeCycleMangerClient.
| name | Managed node name |
| parent_node | Node that execute the service calls |
Definition at line 29 of file lifecycle_manager_client.cpp.
|
protected |
A generic method used to call startup, shutdown, etc.
| command |
Definition at line 108 of file lifecycle_manager_client.cpp.
Referenced by pause(), reset(), resume(), shutdown(), and startup().

| SystemStatus nav2_lifecycle_manager::LifecycleManagerClient::is_active | ( | const std::chrono::nanoseconds | timeout = std::chrono::nanoseconds(-1) | ) |
Check if lifecycle node manager server is active.
Definition at line 77 of file lifecycle_manager_client.cpp.
| bool nav2_lifecycle_manager::LifecycleManagerClient::pause | ( | const std::chrono::nanoseconds | timeout = std::chrono::nanoseconds(-1) | ) |
Make pause service call.
Definition at line 59 of file lifecycle_manager_client.cpp.
References callService().

| bool nav2_lifecycle_manager::LifecycleManagerClient::reset | ( | const std::chrono::nanoseconds | timeout = std::chrono::nanoseconds(-1) | ) |
Make reset service call.
Definition at line 71 of file lifecycle_manager_client.cpp.
References callService().

| bool nav2_lifecycle_manager::LifecycleManagerClient::resume | ( | const std::chrono::nanoseconds | timeout = std::chrono::nanoseconds(-1) | ) |
Make resume service call.
Definition at line 65 of file lifecycle_manager_client.cpp.
References callService().

| bool nav2_lifecycle_manager::LifecycleManagerClient::shutdown | ( | const std::chrono::nanoseconds | timeout = std::chrono::nanoseconds(-1) | ) |
Make shutdown service call.
Definition at line 53 of file lifecycle_manager_client.cpp.
References callService().

| bool nav2_lifecycle_manager::LifecycleManagerClient::startup | ( | const std::chrono::nanoseconds | timeout = std::chrono::nanoseconds(-1) | ) |
Make start up service call.
Definition at line 47 of file lifecycle_manager_client.cpp.
References callService().
