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 "rmw/error_handling.h"
40 #include "rmw/rmw.h"
41 
42 namespace rclcpp
43 {
44 
45 namespace node_interfaces
46 {
47 class NodeBaseInterface;
48 } // namespace node_interfaces
49 
51 {
52 public:
54 
56  ClientBase(
58  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph,
59  const std::string & service_name);
60 
62  virtual ~ClientBase();
63 
65  const std::string &
66  get_service_name() const;
67 
69  rcl_client_t *
71 
73  const rcl_client_t *
74  get_client_handle() const;
75 
77  bool
78  service_is_ready() const;
79 
80  template<typename RatioT = std::milli>
81  bool
84  {
86  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
87  );
88  }
89 
92  virtual void handle_response(
93  std::shared_ptr<rmw_request_id_t> request_header, std::shared_ptr<void> response) = 0;
94 
95 protected:
97 
99  bool
101 
103  rcl_node_t *
105 
107  const rcl_node_t *
108  get_rcl_node_handle() const;
109 
110  rclcpp::node_interfaces::NodeGraphInterface::WeakPtr node_graph_;
112 
115 };
116 
117 template<typename ServiceT>
118 class Client : public ClientBase
119 {
120 public:
121  using SharedRequest = typename ServiceT::Request::SharedPtr;
122  using SharedResponse = typename ServiceT::Response::SharedPtr;
123 
126 
129 
132 
135 
137 
139  rclcpp::node_interfaces::NodeBaseInterface * node_base,
140  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph,
141  const std::string & service_name,
142  rcl_client_options_t & client_options)
143  : ClientBase(node_base, node_graph, service_name)
144  {
145  using rosidl_typesupport_cpp::get_service_type_support_handle;
146  auto service_type_support_handle =
147  get_service_type_support_handle<ServiceT>();
150  this->get_rcl_node_handle(),
151  service_type_support_handle,
152  service_name.c_str(),
153  &client_options);
154  if (ret != RCL_RET_OK) {
155  if (ret == RCL_RET_SERVICE_NAME_INVALID) {
156  auto rcl_node_handle = this->get_rcl_node_handle();
157  // this will throw on any validation problem
158  rcl_reset_error();
160  service_name,
161  rcl_node_get_name(rcl_node_handle),
162  rcl_node_get_namespace(rcl_node_handle),
163  true);
164  }
165  rclcpp::exceptions::throw_from_rcl_error(ret, "could not create client");
166  }
167  }
168 
169  virtual ~Client()
170  {
172  fprintf(stderr,
173  "Error in destruction of rcl client handle: %s\n", rcl_get_error_string_safe());
174  rcl_reset_error();
175  }
176  }
177 
180  {
181  return std::shared_ptr<void>(new typename ServiceT::Response());
182  }
183 
186  {
187  // TODO(wjwwood): This should probably use rmw_request_id's allocator.
188  // (since it is a C type)
190  }
191 
192  void
194  std::shared_ptr<rmw_request_id_t> request_header,
195  std::shared_ptr<void> response)
196  {
197  std::unique_lock<std::mutex> lock(pending_requests_mutex_);
198  auto typed_response = std::static_pointer_cast<typename ServiceT::Response>(response);
199  int64_t sequence_number = request_header->sequence_number;
200  // TODO(esteve) this should throw instead since it is not expected to happen in the first place
201  if (this->pending_requests_.count(sequence_number) == 0) {
202  fprintf(stderr, "Received invalid sequence number. Ignoring...\n");
203  return;
204  }
205  auto tuple = this->pending_requests_[sequence_number];
206  auto call_promise = std::get<0>(tuple);
207  auto callback = std::get<1>(tuple);
208  auto future = std::get<2>(tuple);
209  this->pending_requests_.erase(sequence_number);
210  // Unlock here to allow the service to be called recursively from one of its callbacks.
211  lock.unlock();
212 
213  call_promise->set_value(typed_response);
214  callback(future);
215  }
216 
219  {
220  return async_send_request(request, [](SharedFuture) {});
221  }
222 
223  template<
224  typename CallbackT,
225  typename std::enable_if<
227  CallbackT,
229  >::value
230  >::type * = nullptr
231  >
233  async_send_request(SharedRequest request, CallbackT && cb)
234  {
235  std::lock_guard<std::mutex> lock(pending_requests_mutex_);
236  int64_t sequence_number;
237  rcl_ret_t ret = rcl_send_request(get_client_handle(), request.get(), &sequence_number);
238  if (RCL_RET_OK != ret) {
239  rclcpp::exceptions::throw_from_rcl_error(ret, "failed to send request");
240  }
241 
242  SharedPromise call_promise = std::make_shared<Promise>();
243  SharedFuture f(call_promise->get_future());
244  pending_requests_[sequence_number] =
245  std::make_tuple(call_promise, std::forward<CallbackType>(cb), f);
246  return f;
247  }
248 
249  template<
250  typename CallbackT,
251  typename std::enable_if<
253  CallbackT,
255  >::value
256  >::type * = nullptr
257  >
259  async_send_request(SharedRequest request, CallbackT && cb)
260  {
261  SharedPromiseWithRequest promise = std::make_shared<PromiseWithRequest>();
262  SharedFutureWithRequest future_with_request(promise->get_future());
263 
264  auto wrapping_cb = [future_with_request, promise, request, &cb](SharedFuture future) {
265  auto response = future.get();
266  promise->set_value(std::make_pair(request, response));
267  cb(future_with_request);
268  };
269 
270  async_send_request(request, wrapping_cb);
271 
272  return future_with_request;
273  }
274 
275 private:
277 
279  std::mutex pending_requests_mutex_;
280 };
281 
282 } // namespace rclcpp
283 
284 #endif // RCLCPP__CLIENT_HPP_
SharedFuture async_send_request(SharedRequest request)
Definition: client.hpp:218
#define RCLCPP_DISABLE_COPY(...)
Definition: macros.hpp:26
std::string service_name_
Definition: client.hpp:114
typename rcl_interfaces::srv::GetParameters ::Request::SharedPtr SharedRequest
Definition: client.hpp:121
#define rcl_reset_error
void handle_response(std::shared_ptr< rmw_request_id_t > request_header, std::shared_ptr< void > response)
Definition: client.hpp:193
rmw_ret_t rcl_ret_t
virtual ~ClientBase()
Definition: client.hpp:118
virtual ~Client()
Definition: client.hpp:169
Definition: allocator_common.hpp:24
T make_tuple(T... args)
virtual std::shared_ptr< rmw_request_id_t > create_request_header()=0
rcl_node_t * get_rcl_node_handle()
rcl_client_t client_handle_
Definition: client.hpp:113
rcl_ret_t rcl_send_request(const rcl_client_t *client, const void *ros_request, int64_t *sequence_number)
rcl_client_t * get_client_handle()
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.
bool wait_for_service_nanoseconds(std::chrono::nanoseconds timeout)
rclcpp::node_interfaces::NodeGraphInterface::WeakPtr node_graph_
Definition: client.hpp:110
#define RCL_RET_OK
SharedFuture async_send_request(SharedRequest request, CallbackT &&cb)
Definition: client.hpp:233
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.
std::shared_ptr< rmw_request_id_t > create_request_header()
Definition: client.hpp:185
std::shared_ptr< void > create_response()
Definition: client.hpp:179
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
std::shared_ptr< rcl_node_t > node_handle_
Definition: client.hpp:111
typename rcl_interfaces::srv::GetParameters ::Response::SharedPtr SharedResponse
Definition: client.hpp:122
std::shared_future< std::pair< SharedRequest, SharedResponse > > SharedFutureWithRequest
Definition: client.hpp:131
Definition: function_traits.hpp:143
T make_pair(T... args)
T static_pointer_cast(T... args)
#define rcl_get_error_string_safe
#define RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(...)
Definition: macros.hpp:51
std::function< void(SharedFutureWithRequest)> CallbackWithRequestType
Definition: client.hpp:134
T get(T... args)
std::function< void(SharedFuture)> CallbackType
Definition: client.hpp:133
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
Pure virtual interface class for the NodeBase part of the Node API.
Definition: node_base_interface.hpp:36
#define RCL_RET_SERVICE_NAME_INVALID
const char * rcl_node_get_name(const rcl_node_t *node)
virtual void handle_response(std::shared_ptr< rmw_request_id_t > request_header, std::shared_ptr< void > response)=0
const char * rcl_node_get_namespace(const rcl_node_t *node)
std::shared_future< SharedResponse > SharedFuture
Definition: client.hpp:130
rcl_client_t rcl_get_zero_initialized_client(void)
rcl_ret_t rcl_client_fini(rcl_client_t *client, rcl_node_t *node)
SharedFutureWithRequest async_send_request(SharedRequest request, CallbackT &&cb)
Definition: client.hpp:259
ClientBase(rclcpp::node_interfaces::NodeBaseInterface *node_base, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph, const std::string &service_name)
bool service_is_ready() const
Definition: client.hpp:50
bool wait_for_service(std::chrono::duration< int64_t, RatioT > timeout=std::chrono::duration< int64_t, RatioT >(-1))
Definition: client.hpp:82
virtual std::shared_ptr< void > create_response()=0
const std::string & get_service_name() const