Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
lifecycle_manager_client.cpp
1 // Copyright (c) 2019 Intel Corporation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include "nav2_lifecycle_manager/lifecycle_manager_client.hpp"
16 
17 #include <cmath>
18 #include <memory>
19 #include <string>
20 #include <utility>
21 
22 #include "nav2_util/geometry_utils.hpp"
23 
24 namespace nav2_lifecycle_manager
25 {
26 using nav2_util::geometry_utils::orientationAroundZAxis;
27 
29  const std::string & name,
30  std::shared_ptr<rclcpp::Node> parent_node)
31 {
32  manage_service_name_ = name + std::string("/manage_nodes");
33  active_service_name_ = name + std::string("/is_active");
34 
35  // Use parent node for service call and logging
36  node_ = parent_node;
37 
38  // Create the service clients
39  manager_client_ = std::make_shared<nav2_util::ServiceClient<ManageLifecycleNodes>>(
40  manage_service_name_, node_, true /*creates and spins an internal executor*/);
41  is_active_client_ = std::make_shared<nav2_util::ServiceClient<std_srvs::srv::Trigger>>(
42  active_service_name_, node_, true /*creates and spins an internal executor*/);
43 }
44 
45 bool
46 LifecycleManagerClient::startup(const std::chrono::nanoseconds timeout)
47 {
48  return callService(ManageLifecycleNodes::Request::STARTUP, timeout);
49 }
50 
51 bool
52 LifecycleManagerClient::shutdown(const std::chrono::nanoseconds timeout)
53 {
54  return callService(ManageLifecycleNodes::Request::SHUTDOWN, timeout);
55 }
56 
57 bool
58 LifecycleManagerClient::pause(const std::chrono::nanoseconds timeout)
59 {
60  return callService(ManageLifecycleNodes::Request::PAUSE, timeout);
61 }
62 
63 bool
64 LifecycleManagerClient::resume(const std::chrono::nanoseconds timeout)
65 {
66  return callService(ManageLifecycleNodes::Request::RESUME, timeout);
67 }
68 
69 bool
70 LifecycleManagerClient::reset(const std::chrono::nanoseconds timeout)
71 {
72  return callService(ManageLifecycleNodes::Request::RESET, timeout);
73 }
74 
75 bool
76 LifecycleManagerClient::configure(const std::chrono::nanoseconds timeout)
77 {
78  return callService(ManageLifecycleNodes::Request::CONFIGURE, timeout);
79 }
80 
81 bool
82 LifecycleManagerClient::cleanup(const std::chrono::nanoseconds timeout)
83 {
84  return callService(ManageLifecycleNodes::Request::CLEANUP, timeout);
85 }
86 
87 SystemStatus
88 LifecycleManagerClient::is_active(const std::chrono::nanoseconds timeout)
89 {
90  auto request = std::make_shared<std_srvs::srv::Trigger::Request>();
91  auto response = std::make_shared<std_srvs::srv::Trigger::Response>();
92 
93  RCLCPP_DEBUG(
94  node_->get_logger(), "Waiting for the %s service...",
95  active_service_name_.c_str());
96 
97  if (!is_active_client_->wait_for_service(std::chrono::seconds(1))) {
98  return SystemStatus::TIMEOUT;
99  }
100 
101  RCLCPP_DEBUG(
102  node_->get_logger(), "Sending %s request",
103  active_service_name_.c_str());
104 
105  try {
106  response = is_active_client_->invoke(request, timeout);
107  } catch (std::runtime_error &) {
108  return SystemStatus::TIMEOUT;
109  }
110 
111  if (response->success) {
112  return SystemStatus::ACTIVE;
113  } else {
114  return SystemStatus::INACTIVE;
115  }
116 }
117 
118 bool
119 LifecycleManagerClient::callService(uint8_t command, const std::chrono::nanoseconds timeout)
120 {
121  auto request = std::make_shared<ManageLifecycleNodes::Request>();
122  request->command = command;
123 
124  RCLCPP_DEBUG(
125  node_->get_logger(), "Waiting for the %s service...",
126  manage_service_name_.c_str());
127 
128  while (!manager_client_->wait_for_service(timeout)) {
129  if (!rclcpp::ok()) {
130  RCLCPP_ERROR(node_->get_logger(), "Client interrupted while waiting for service to appear");
131  return false;
132  }
133  RCLCPP_DEBUG(node_->get_logger(), "Waiting for service to appear...");
134  }
135 
136  RCLCPP_DEBUG(
137  node_->get_logger(), "Sending %s request",
138  manage_service_name_.c_str());
139  try {
140  auto future_result = manager_client_->invoke(request, timeout);
141  return future_result->success;
142  } catch (std::runtime_error &) {
143  return false;
144  }
145 }
146 
147 } // namespace nav2_lifecycle_manager
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.