Nav2 Navigation Stack - jazzy  jazzy
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 "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
23 #include "nav2_util/geometry_utils.hpp"
24 
25 namespace nav2_lifecycle_manager
26 {
27 using nav2_util::geometry_utils::orientationAroundZAxis;
28 
30  const std::string & name,
31  std::shared_ptr<rclcpp::Node> parent_node)
32 {
33  manage_service_name_ = name + std::string("/manage_nodes");
34  active_service_name_ = name + std::string("/is_active");
35 
36  // Use parent node for service call and logging
37  node_ = parent_node;
38 
39  // Create the service clients
40  manager_client_ = std::make_shared<nav2_util::ServiceClient<ManageLifecycleNodes>>(
41  manage_service_name_, node_);
42  is_active_client_ = std::make_shared<nav2_util::ServiceClient<std_srvs::srv::Trigger>>(
43  active_service_name_, node_);
44 }
45 
46 bool
47 LifecycleManagerClient::startup(const std::chrono::nanoseconds timeout)
48 {
49  return callService(ManageLifecycleNodes::Request::STARTUP, timeout);
50 }
51 
52 bool
53 LifecycleManagerClient::shutdown(const std::chrono::nanoseconds timeout)
54 {
55  return callService(ManageLifecycleNodes::Request::SHUTDOWN, timeout);
56 }
57 
58 bool
59 LifecycleManagerClient::pause(const std::chrono::nanoseconds timeout)
60 {
61  return callService(ManageLifecycleNodes::Request::PAUSE, timeout);
62 }
63 
64 bool
65 LifecycleManagerClient::resume(const std::chrono::nanoseconds timeout)
66 {
67  return callService(ManageLifecycleNodes::Request::RESUME, timeout);
68 }
69 
70 bool
71 LifecycleManagerClient::reset(const std::chrono::nanoseconds timeout)
72 {
73  return callService(ManageLifecycleNodes::Request::RESET, timeout);
74 }
75 
76 bool
77 LifecycleManagerClient::configure(const std::chrono::nanoseconds timeout)
78 {
79  return callService(ManageLifecycleNodes::Request::CONFIGURE, timeout);
80 }
81 
82 bool
83 LifecycleManagerClient::cleanup(const std::chrono::nanoseconds timeout)
84 {
85  return callService(ManageLifecycleNodes::Request::CLEANUP, timeout);
86 }
87 
88 SystemStatus
89 LifecycleManagerClient::is_active(const std::chrono::nanoseconds timeout)
90 {
91  auto request = std::make_shared<std_srvs::srv::Trigger::Request>();
92  auto response = std::make_shared<std_srvs::srv::Trigger::Response>();
93 
94  RCLCPP_DEBUG(
95  node_->get_logger(), "Waiting for the %s service...",
96  active_service_name_.c_str());
97 
98  if (!is_active_client_->wait_for_service(std::chrono::seconds(1))) {
99  return SystemStatus::TIMEOUT;
100  }
101 
102  RCLCPP_DEBUG(
103  node_->get_logger(), "Sending %s request",
104  active_service_name_.c_str());
105 
106  try {
107  response = is_active_client_->invoke(request, timeout);
108  } catch (std::runtime_error &) {
109  return SystemStatus::TIMEOUT;
110  }
111 
112  if (response->success) {
113  return SystemStatus::ACTIVE;
114  } else {
115  return SystemStatus::INACTIVE;
116  }
117 }
118 
119 bool
120 LifecycleManagerClient::callService(uint8_t command, const std::chrono::nanoseconds timeout)
121 {
122  auto request = std::make_shared<ManageLifecycleNodes::Request>();
123  request->command = command;
124 
125  RCLCPP_DEBUG(
126  node_->get_logger(), "Waiting for the %s service...",
127  manage_service_name_.c_str());
128 
129  while (!manager_client_->wait_for_service(timeout)) {
130  if (!rclcpp::ok()) {
131  RCLCPP_ERROR(node_->get_logger(), "Client interrupted while waiting for service to appear");
132  return false;
133  }
134  RCLCPP_DEBUG(node_->get_logger(), "Waiting for service to appear...");
135  }
136 
137  RCLCPP_DEBUG(
138  node_->get_logger(), "Sending %s request",
139  manage_service_name_.c_str());
140  try {
141  auto future_result = manager_client_->invoke(request, timeout);
142  return future_result->success;
143  } catch (std::runtime_error &) {
144  return false;
145  }
146 }
147 
148 } // 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.