15 #include "nav2_lifecycle_manager/lifecycle_manager_client.hpp"
22 #include "nav2_util/geometry_utils.hpp"
24 namespace nav2_lifecycle_manager
26 using nav2_util::geometry_utils::orientationAroundZAxis;
29 const std::string & name,
30 std::shared_ptr<rclcpp::Node> parent_node)
32 manage_service_name_ = name + std::string(
"/manage_nodes");
33 active_service_name_ = name + std::string(
"/is_active");
39 manager_client_ = std::make_shared<nav2_util::ServiceClient<ManageLifecycleNodes>>(
40 manage_service_name_, node_,
true );
41 is_active_client_ = std::make_shared<nav2_util::ServiceClient<std_srvs::srv::Trigger>>(
42 active_service_name_, node_,
true );
48 return callService(ManageLifecycleNodes::Request::STARTUP, timeout);
54 return callService(ManageLifecycleNodes::Request::SHUTDOWN, timeout);
60 return callService(ManageLifecycleNodes::Request::PAUSE, timeout);
66 return callService(ManageLifecycleNodes::Request::RESUME, timeout);
72 return callService(ManageLifecycleNodes::Request::RESET, timeout);
78 return callService(ManageLifecycleNodes::Request::CONFIGURE, timeout);
84 return callService(ManageLifecycleNodes::Request::CLEANUP, timeout);
90 auto request = std::make_shared<std_srvs::srv::Trigger::Request>();
91 auto response = std::make_shared<std_srvs::srv::Trigger::Response>();
94 node_->get_logger(),
"Waiting for the %s service...",
95 active_service_name_.c_str());
98 return SystemStatus::TIMEOUT;
102 node_->get_logger(),
"Sending %s request",
103 active_service_name_.c_str());
106 response = is_active_client_->
invoke(request, timeout);
107 }
catch (std::runtime_error &) {
108 return SystemStatus::TIMEOUT;
111 if (response->success) {
112 return SystemStatus::ACTIVE;
114 return SystemStatus::INACTIVE;
121 auto request = std::make_shared<ManageLifecycleNodes::Request>();
122 request->command = command;
125 node_->get_logger(),
"Waiting for the %s service...",
126 manage_service_name_.c_str());
130 RCLCPP_ERROR(node_->get_logger(),
"Client interrupted while waiting for service to appear");
133 RCLCPP_DEBUG(node_->get_logger(),
"Waiting for service to appear...");
137 node_->get_logger(),
"Sending %s request",
138 manage_service_name_.c_str());
140 auto future_result = manager_client_->
invoke(request, timeout);
141 return future_result->success;
142 }
catch (std::runtime_error &) {
bool cleanup(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make cleanup service call.
LifecycleManagerClient(const std::string &name, std::shared_ptr< rclcpp::Node > parent_node)
A constructor for LifeCycleMangerClient.
bool pause(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make pause service call.
SystemStatus is_active(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Check if lifecycle node manager server is active.
bool shutdown(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make shutdown service call.
bool reset(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make reset service call.
bool startup(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make start up service call.
bool configure(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make configure service call.
bool callService(uint8_t command, const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
A generic method used to call startup, shutdown, etc.
bool resume(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make resume service call.
ResponseType::SharedPtr invoke(typename RequestType::SharedPtr &request, const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Invoke the service and block until completed or timed out.
bool wait_for_service(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds::max())
Block until a service is available or timeout.