rclcpp  master
C++ ROS Client Library API
client.hpp
Go to the documentation of this file.
1 // Copyright 2014 Open Source Robotics Foundation, Inc.
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 RCLCPP__CLIENT_HPP_
16 #define RCLCPP__CLIENT_HPP_
17 
18 #include <future>
19 #include <map>
20 #include <memory>
21 #include <sstream>
22 #include <string>
23 #include <tuple>
24 #include <utility>
25 
26 #include "rcl/client.h"
27 #include "rcl/error_handling.h"
28 #include "rcl/wait.h"
29 
30 #include "rclcpp/exceptions.hpp"
32 #include "rclcpp/macros.hpp"
35 #include "rclcpp/utilities.hpp"
38 
39 #include "rcutils/logging_macros.h"
40 
41 #include "rmw/error_handling.h"
42 #include "rmw/rmw.h"
43 
44 namespace rclcpp
45 {
46 
47 namespace node_interfaces
48 {
49 class NodeBaseInterface;
50 } // namespace node_interfaces
51 
53 {
54 public:
56 
58  ClientBase(
60  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph);
61 
63  virtual ~ClientBase();
64 
66  const char *
67  get_service_name() const;
68 
71  get_client_handle();
72 
75  get_client_handle() const;
76 
78  bool
79  service_is_ready() const;
80 
81  template<typename RepT = int64_t, typename RatioT = std::milli>
82  bool
85  {
86  return wait_for_service_nanoseconds(
87  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
88  );
89  }
90 
91  virtual std::shared_ptr<void> create_response() = 0;
92  virtual std::shared_ptr<rmw_request_id_t> create_request_header() = 0;
93  virtual void handle_response(
94  std::shared_ptr<rmw_request_id_t> request_header, std::shared_ptr<void> response) = 0;
95 
96 protected:
97  RCLCPP_DISABLE_COPY(ClientBase)
98 
100  bool
101  wait_for_service_nanoseconds(std::chrono::nanoseconds timeout);
102 
104  rcl_node_t *
105  get_rcl_node_handle();
106 
108  const rcl_node_t *
109  get_rcl_node_handle() const;
110 
111  rclcpp::node_interfaces::NodeGraphInterface::WeakPtr node_graph_;
114 
116 };
117 
118 template<typename ServiceT>
119 class Client : public ClientBase
120 {
121 public:
122  using SharedRequest = typename ServiceT::Request::SharedPtr;
123  using SharedResponse = typename ServiceT::Response::SharedPtr;
124 
127 
130 
133 
136 
138 
140  rclcpp::node_interfaces::NodeBaseInterface * node_base,
141  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph,
142  const std::string & service_name,
143  rcl_client_options_t & client_options)
144  : ClientBase(node_base, node_graph)
145  {
146  using rosidl_typesupport_cpp::get_service_type_support_handle;
147  auto service_type_support_handle =
148  get_service_type_support_handle<ServiceT>();
150  this->get_client_handle().get(),
151  this->get_rcl_node_handle(),
152  service_type_support_handle,
153  service_name.c_str(),
154  &client_options);
155  if (ret != RCL_RET_OK) {
156  if (ret == RCL_RET_SERVICE_NAME_INVALID) {
157  auto rcl_node_handle = this->get_rcl_node_handle();
158  // this will throw on any validation problem
159  rcl_reset_error();
161  service_name,
162  rcl_node_get_name(rcl_node_handle),
163  rcl_node_get_namespace(rcl_node_handle),
164  true);
165  }
166  rclcpp::exceptions::throw_from_rcl_error(ret, "could not create client");
167  }
168  }
169 
170  virtual ~Client()
171  {
172  }
173 
175  create_response() override
176  {
177  return std::shared_ptr<void>(new typename ServiceT::Response());
178  }
179 
182  {
183  // TODO(wjwwood): This should probably use rmw_request_id's allocator.
184  // (since it is a C type)
186  }
187 
188  void
190  std::shared_ptr<rmw_request_id_t> request_header,
191  std::shared_ptr<void> response) override
192  {
193  std::unique_lock<std::mutex> lock(pending_requests_mutex_);
194  auto typed_response = std::static_pointer_cast<typename ServiceT::Response>(response);
195  int64_t sequence_number = request_header->sequence_number;
196  // TODO(esteve) this should throw instead since it is not expected to happen in the first place
197  if (this->pending_requests_.count(sequence_number) == 0) {
199  "rclcpp",
200  "Received invalid sequence number. Ignoring...");
201  return;
202  }
203  auto tuple = this->pending_requests_[sequence_number];
204  auto call_promise = std::get<0>(tuple);
205  auto callback = std::get<1>(tuple);
206  auto future = std::get<2>(tuple);
207  this->pending_requests_.erase(sequence_number);
208  // Unlock here to allow the service to be called recursively from one of its callbacks.
209  lock.unlock();
210 
211  call_promise->set_value(typed_response);
212  callback(future);
213  }
214 
217  {
218  return async_send_request(request, [](SharedFuture) {});
219  }
220 
221  template<
222  typename CallbackT,
223  typename std::enable_if<
225  CallbackT,
227  >::value
228  >::type * = nullptr
229  >
231  async_send_request(SharedRequest request, CallbackT && cb)
232  {
233  std::lock_guard<std::mutex> lock(pending_requests_mutex_);
234  int64_t sequence_number;
235  rcl_ret_t ret = rcl_send_request(get_client_handle().get(), request.get(), &sequence_number);
236  if (RCL_RET_OK != ret) {
237  rclcpp::exceptions::throw_from_rcl_error(ret, "failed to send request");
238  }
239 
240  SharedPromise call_promise = std::make_shared<Promise>();
241  SharedFuture f(call_promise->get_future());
242  pending_requests_[sequence_number] =
243  std::make_tuple(call_promise, std::forward<CallbackType>(cb), f);
244  return f;
245  }
246 
247  template<
248  typename CallbackT,
249  typename std::enable_if<
251  CallbackT,
253  >::value
254  >::type * = nullptr
255  >
257  async_send_request(SharedRequest request, CallbackT && cb)
258  {
259  SharedPromiseWithRequest promise = std::make_shared<PromiseWithRequest>();
260  SharedFutureWithRequest future_with_request(promise->get_future());
261 
262  auto wrapping_cb = [future_with_request, promise, request, &cb](SharedFuture future) {
263  auto response = future.get();
264  promise->set_value(std::make_pair(request, response));
265  cb(future_with_request);
266  };
267 
268  async_send_request(request, wrapping_cb);
269 
270  return future_with_request;
271  }
272 
273 private:
275 
277  std::mutex pending_requests_mutex_;
278 };
279 
280 } // namespace rclcpp
281 
282 #endif // RCLCPP__CLIENT_HPP_
Definition: client.hpp:52
std::shared_ptr< rcl_client_t > client_handle_
Definition: client.hpp:115
std::shared_ptr< rclcpp::Context > context_
Definition: client.hpp:113
T unlock(T... args)
SharedFuture async_send_request(SharedRequest request)
Definition: client.hpp:216
#define RCLCPP_DISABLE_COPY(...)
Definition: macros.hpp:26
#define rcl_reset_error
rmw_ret_t rcl_ret_t
bool wait_for_service(std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Definition: client.hpp:83
void handle_response(std::shared_ptr< rmw_request_id_t > request_header, std::shared_ptr< void > response) override
Definition: client.hpp:189
std::shared_ptr< rmw_request_id_t > create_request_header() override
Definition: client.hpp:181
This header provides the get_node_topics_interface() template function.
Definition: allocator_common.hpp:24
T make_tuple(T... args)
typename rcl_interfaces::srv::GetParameters ::Request::SharedPtr SharedRequest
Definition: client.hpp:122
rcl_ret_t rcl_send_request(const rcl_client_t *client, const void *ros_request, int64_t *sequence_number)
std::string expand_topic_or_service_name(const std::string &name, const std::string &node_name, const std::string &namespace_, bool is_service=false)
Expand a topic or service name and throw if it is not valid.
Definition: client.hpp:119
rclcpp::node_interfaces::NodeGraphInterface::WeakPtr node_graph_
Definition: client.hpp:111
#define RCL_RET_OK
void throw_from_rcl_error(rcl_ret_t ret, const std::string &prefix="", const rcl_error_state_t *error_state=nullptr, void(*reset_error)()=rcl_reset_error)
Throw a C++ std::exception which was created based on an rcl error.
rcl_ret_t rcl_client_init(rcl_client_t *client, const rcl_node_t *node, const rosidl_service_type_support_t *type_support, const char *service_name, const rcl_client_options_t *options)
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
Definition: function_traits.hpp:143
Pure virtual interface class for the NodeBase part of the Node API.
Definition: node_base_interface.hpp:36
T make_pair(T... args)
T static_pointer_cast(T... args)
#define RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(...)
Definition: macros.hpp:51
#define RCUTILS_LOG_ERROR_NAMED(name,...)
SharedFuture async_send_request(SharedRequest request, CallbackT &&cb)
Definition: client.hpp:231
T get(T... args)
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
typename rcl_interfaces::srv::GetParameters ::Response::SharedPtr SharedResponse
Definition: client.hpp:123
virtual ~Client()
Definition: client.hpp:170
#define RCL_RET_SERVICE_NAME_INVALID
SharedFutureWithRequest async_send_request(SharedRequest request, CallbackT &&cb)
Definition: client.hpp:257
std::shared_ptr< void > create_response() override
Definition: client.hpp:175
const char * rcl_node_get_name(const rcl_node_t *node)
const char * rcl_node_get_namespace(const rcl_node_t *node)
std::shared_ptr< rcl_node_t > node_handle_
Definition: client.hpp:112