Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
service_client.hpp
1 // Copyright (c) 2018 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 #ifndef NAV2_UTIL__SERVICE_CLIENT_HPP_
16 #define NAV2_UTIL__SERVICE_CLIENT_HPP_
17 
18 #include <string>
19 
20 #include "rclcpp/rclcpp.hpp"
21 
22 namespace nav2_util
23 {
24 
29 template<class ServiceT, typename NodeT = rclcpp::Node::SharedPtr>
31 {
32 public:
38  explicit ServiceClient(
39  const std::string & service_name,
40  const NodeT & provided_node)
41  : service_name_(service_name), node_(provided_node)
42  {
43  callback_group_ = node_->create_callback_group(
44  rclcpp::CallbackGroupType::MutuallyExclusive,
45  false);
46  callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
47  client_ = node_->template create_client<ServiceT>(
48  service_name,
49  rclcpp::SystemDefaultsQoS(),
50  callback_group_);
51  }
52 
53  using RequestType = typename ServiceT::Request;
54  using ResponseType = typename ServiceT::Response;
55 
62  typename ResponseType::SharedPtr invoke(
63  typename RequestType::SharedPtr & request,
64  const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1))
65  {
66  while (!client_->wait_for_service(std::chrono::seconds(1))) {
67  if (!rclcpp::ok()) {
68  throw std::runtime_error(
69  service_name_ + " service client: interrupted while waiting for service");
70  }
71  RCLCPP_INFO(
72  node_->get_logger(), "%s service client: waiting for service to appear...",
73  service_name_.c_str());
74  }
75 
76  RCLCPP_DEBUG(
77  node_->get_logger(), "%s service client: send async request",
78  service_name_.c_str());
79  auto future_result = client_->async_send_request(request);
80 
81  if (callback_group_executor_.spin_until_future_complete(future_result, timeout) !=
82  rclcpp::FutureReturnCode::SUCCESS)
83  {
84  // Pending request must be manually cleaned up if execution is interrupted or timed out
85  client_->remove_pending_request(future_result);
86  throw std::runtime_error(service_name_ + " service client: async_send_request failed");
87  }
88 
89  return future_result.get();
90  }
91 
98  bool invoke(
99  typename RequestType::SharedPtr & request,
100  typename ResponseType::SharedPtr & response)
101  {
102  while (!client_->wait_for_service(std::chrono::seconds(1))) {
103  if (!rclcpp::ok()) {
104  throw std::runtime_error(
105  service_name_ + " service client: interrupted while waiting for service");
106  }
107  RCLCPP_INFO(
108  node_->get_logger(), "%s service client: waiting for service to appear...",
109  service_name_.c_str());
110  }
111 
112  RCLCPP_DEBUG(
113  node_->get_logger(), "%s service client: send async request",
114  service_name_.c_str());
115  auto future_result = client_->async_send_request(request);
116 
117  if (callback_group_executor_.spin_until_future_complete(future_result) !=
118  rclcpp::FutureReturnCode::SUCCESS)
119  {
120  // Pending request must be manually cleaned up if execution is interrupted or timed out
121  client_->remove_pending_request(future_result);
122  return false;
123  }
124 
125  response = future_result.get();
126  return response.get();
127  }
128 
134  bool wait_for_service(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds::max())
135  {
136  return client_->wait_for_service(timeout);
137  }
138 
143  std::string getServiceName()
144  {
145  return service_name_;
146  }
147 
148 protected:
149  std::string service_name_;
150  NodeT node_;
151  rclcpp::CallbackGroup::SharedPtr callback_group_;
152  rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
153  typename rclcpp::Client<ServiceT>::SharedPtr client_;
154 };
155 
156 } // namespace nav2_util
157 
158 #endif // NAV2_UTIL__SERVICE_CLIENT_HPP_
A simple wrapper on ROS2 services for invoke() and block-style calling.
bool invoke(typename RequestType::SharedPtr &request, typename ResponseType::SharedPtr &response)
Invoke the service and block until completed.
ServiceClient(const std::string &service_name, const NodeT &provided_node)
A constructor.
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.
std::string getServiceName()
Gets the service name.
bool wait_for_service(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds::max())
Block until a service is available or timeout.