Nav2 Navigation Stack - rolling  main
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_ROS_COMMON__SERVICE_CLIENT_HPP_
16 #define NAV2_ROS_COMMON__SERVICE_CLIENT_HPP_
17 
18 #include <string>
19 #include <memory>
20 #include <chrono>
21 #include "rclcpp/rclcpp.hpp"
22 #include "nav2_ros_common/node_utils.hpp"
23 
24 namespace nav2
25 {
26 
31 template<typename ServiceT>
33 {
34 public:
35  using SharedPtr = std::shared_ptr<nav2::ServiceClient<ServiceT>>;
36  using UniquePtr = std::unique_ptr<nav2::ServiceClient<ServiceT>>;
37 
44  template<typename NodeT>
45  explicit ServiceClient(
46  const std::string & service_name,
47  const NodeT & provided_node, bool use_internal_executor = false)
48  : service_name_(service_name),
49  clock_(provided_node->get_clock()),
50  logger_(provided_node->get_logger()),
51  node_base_interface_(provided_node->get_node_base_interface()),
52  use_internal_executor_(use_internal_executor)
53  {
54  if (use_internal_executor) {
55  callback_group_ = provided_node->create_callback_group(
56  rclcpp::CallbackGroupType::MutuallyExclusive,
57  false);
58  callback_group_executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
59  callback_group_executor_->add_callback_group(callback_group_,
60  provided_node->get_node_base_interface());
61  }
62  // When a nullptr is passed, the client will use the default callback group
63  client_ = rclcpp::create_client<ServiceT>(
64  provided_node->get_node_base_interface(),
65  provided_node->get_node_graph_interface(),
66  provided_node->get_node_services_interface(),
67  service_name,
68  rclcpp::ServicesQoS(), // Use consistent QoS settings
69  callback_group_);
70 
71  nav2::setIntrospectionMode(this->client_,
72  provided_node->get_node_parameters_interface(), clock_);
73  }
74 
75  using RequestType = typename ServiceT::Request;
76  using ResponseType = typename ServiceT::Response;
77 
84  typename ResponseType::SharedPtr invoke(
85  typename RequestType::SharedPtr & request,
86  const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1),
87  const std::chrono::nanoseconds wait_for_service_timeout = std::chrono::seconds(10))
88  {
89  auto now = clock_->now();
90  while (!client_->wait_for_service(std::chrono::seconds(1))) {
91  if (!rclcpp::ok()) {
92  throw std::runtime_error(
93  service_name_ + " service client: interrupted while waiting for service");
94  }
95  RCLCPP_INFO(
96  logger_, "%s service client: waiting for service to appear...",
97  service_name_.c_str());
98 
99  if (clock_->now() - now > wait_for_service_timeout) {
100  throw std::runtime_error(
101  service_name_ + " service client: timed out waiting for service");
102  }
103  }
104 
105  RCLCPP_DEBUG(
106  logger_, "%s service client: send async request",
107  service_name_.c_str());
108  auto future_result = client_->async_send_request(request);
109  if (spin_until_complete(future_result, timeout) != rclcpp::FutureReturnCode::SUCCESS) {
110  // Pending request must be manually cleaned up if execution is interrupted or timed out
111  client_->remove_pending_request(future_result);
112  throw std::runtime_error(service_name_ + " service client: async_send_request failed");
113  }
114 
115  return future_result.get();
116  }
117 
124  bool invoke(
125  typename RequestType::SharedPtr & request,
126  typename ResponseType::SharedPtr & response,
127  const std::chrono::nanoseconds wait_for_service_timeout = std::chrono::seconds(10))
128  {
129  auto now = clock_->now();
130  while (!client_->wait_for_service(std::chrono::seconds(1))) {
131  if (!rclcpp::ok()) {
132  throw std::runtime_error(
133  service_name_ + " service client: interrupted while waiting for service");
134  }
135  RCLCPP_INFO(
136  logger_, "%s service client: waiting for service to appear...",
137  service_name_.c_str());
138 
139  if (clock_->now() - now > wait_for_service_timeout) {
140  throw std::runtime_error(
141  service_name_ + " service client: timed out waiting for service");
142  }
143  }
144 
145  RCLCPP_DEBUG(
146  logger_, "%s service client: send async request",
147  service_name_.c_str());
148  auto future_result = client_->async_send_request(request);
149  if (spin_until_complete(future_result) != rclcpp::FutureReturnCode::SUCCESS) {
150  // Pending request must be manually cleaned up if execution is interrupted or timed out
151  client_->remove_pending_request(future_result);
152  return false;
153  }
154 
155  response = future_result.get();
156  return response.get();
157  }
158 
164  std::shared_future<typename ResponseType::SharedPtr> async_call(
165  typename RequestType::SharedPtr & request)
166  {
167  auto future_result = client_->async_send_request(request);
168  return future_result.share();
169  }
170 
171 
177  template<typename CallbackT>
178  void async_call(typename RequestType::SharedPtr request, CallbackT && callback)
179  {
180  client_->async_send_request(request, callback);
181  }
182 
188  bool wait_for_service(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds::max())
189  {
190  return client_->wait_for_service(timeout);
191  }
192 
200  template<typename FutureT>
201  rclcpp::FutureReturnCode spin_until_complete(
202  const FutureT & future,
203  const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1))
204  {
205  if (use_internal_executor_) {
206  return callback_group_executor_->spin_until_future_complete(future, timeout);
207  } else {
208  return rclcpp::spin_until_future_complete(node_base_interface_, future, timeout);
209  }
210  }
211 
216  std::string getServiceName()
217  {
218  return service_name_;
219  }
220 
221 protected:
222  std::string service_name_;
223  rclcpp::Clock::SharedPtr clock_;
224  rclcpp::Logger logger_{rclcpp::get_logger("nav2_ros_common")};
225  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;
226  rclcpp::CallbackGroup::SharedPtr callback_group_{nullptr};
227  rclcpp::executors::SingleThreadedExecutor::SharedPtr callback_group_executor_;
228  typename rclcpp::Client<ServiceT>::SharedPtr client_;
229  bool use_internal_executor_;
230 };
231 
232 } // namespace nav2
233 
234 #endif // NAV2_ROS_COMMON__SERVICE_CLIENT_HPP_
A simple wrapper on ROS2 services client.
std::shared_future< typename ResponseType::SharedPtr > async_call(typename RequestType::SharedPtr &request)
Asynchronously call the service.
rclcpp::FutureReturnCode spin_until_complete(const FutureT &future, const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Spins the executor until the provided future is complete or the timeout is reached.
ResponseType::SharedPtr invoke(typename RequestType::SharedPtr &request, const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1), const std::chrono::nanoseconds wait_for_service_timeout=std::chrono::seconds(10))
Invoke the service and block until completed or timed out.
void async_call(typename RequestType::SharedPtr request, CallbackT &&callback)
Asynchronously call the service with a callback.
bool invoke(typename RequestType::SharedPtr &request, typename ResponseType::SharedPtr &response, const std::chrono::nanoseconds wait_for_service_timeout=std::chrono::seconds(10))
Invoke the service and block until completed.
ServiceClient(const std::string &service_name, const NodeT &provided_node, bool use_internal_executor=false)
A constructor.
bool wait_for_service(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds::max())
Block until a service is available or timeout.
std::string getServiceName()
Gets the service name.