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 <atomic>
19 #include <future>
20 #include <map>
21 #include <memory>
22 #include <sstream>
23 #include <string>
24 #include <tuple>
25 #include <utility>
26 
27 #include "rcl/client.h"
28 #include "rcl/error_handling.h"
29 #include "rcl/wait.h"
30 
31 #include "rclcpp/exceptions.hpp"
33 #include "rclcpp/macros.hpp"
36 #include "rclcpp/utilities.hpp"
39 
40 #include "rcutils/logging_macros.h"
41 
42 #include "rmw/error_handling.h"
43 #include "rmw/rmw.h"
44 
45 namespace rclcpp
46 {
47 
48 namespace node_interfaces
49 {
50 class NodeBaseInterface;
51 } // namespace node_interfaces
52 
54 {
55 public:
57 
59  ClientBase(
61  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph);
62 
64  virtual ~ClientBase();
65 
67 
84  bool
85  take_type_erased_response(void * response_out, rmw_request_id_t & request_header_out);
86 
88 
90  const char *
91  get_service_name() const;
92 
94 
101 
103 
109  get_client_handle() const;
110 
112 
116  bool
117  service_is_ready() const;
118 
120 
124  template<typename RepT = int64_t, typename RatioT = std::milli>
125  bool
128  {
130  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
131  );
132  }
133 
136  virtual void handle_response(
137  std::shared_ptr<rmw_request_id_t> request_header, std::shared_ptr<void> response) = 0;
138 
140 
150  bool
151  exchange_in_use_by_wait_set_state(bool in_use_state);
152 
153 protected:
155 
157  bool
159 
161  rcl_node_t *
163 
165  const rcl_node_t *
166  get_rcl_node_handle() const;
167 
168  rclcpp::node_interfaces::NodeGraphInterface::WeakPtr node_graph_;
171 
173 
175 };
176 
177 template<typename ServiceT>
178 class Client : public ClientBase
179 {
180 public:
181  using SharedRequest = typename ServiceT::Request::SharedPtr;
182  using SharedResponse = typename ServiceT::Response::SharedPtr;
183 
186 
189 
192 
195 
197 
198 
199 
210  rclcpp::node_interfaces::NodeBaseInterface * node_base,
211  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph,
212  const std::string & service_name,
213  rcl_client_options_t & client_options)
214  : ClientBase(node_base, node_graph)
215  {
216  using rosidl_typesupport_cpp::get_service_type_support_handle;
217  auto service_type_support_handle =
218  get_service_type_support_handle<ServiceT>();
220  this->get_client_handle().get(),
221  this->get_rcl_node_handle(),
222  service_type_support_handle,
223  service_name.c_str(),
224  &client_options);
225  if (ret != RCL_RET_OK) {
226  if (ret == RCL_RET_SERVICE_NAME_INVALID) {
227  auto rcl_node_handle = this->get_rcl_node_handle();
228  // this will throw on any validation problem
229  rcl_reset_error();
231  service_name,
232  rcl_node_get_name(rcl_node_handle),
233  rcl_node_get_namespace(rcl_node_handle),
234  true);
235  }
236  rclcpp::exceptions::throw_from_rcl_error(ret, "could not create client");
237  }
238  }
239 
240  virtual ~Client()
241  {
242  }
243 
245 
257  bool
258  take_response(typename ServiceT::Response & response_out, rmw_request_id_t & request_header_out)
259  {
260  return this->take_type_erased_response(&response_out, request_header_out);
261  }
262 
264 
268  create_response() override
269  {
270  return std::shared_ptr<void>(new typename ServiceT::Response());
271  }
272 
274 
279  {
280  // TODO(wjwwood): This should probably use rmw_request_id's allocator.
281  // (since it is a C type)
283  }
284 
286 
290  void
292  std::shared_ptr<rmw_request_id_t> request_header,
293  std::shared_ptr<void> response) override
294  {
295  std::unique_lock<std::mutex> lock(pending_requests_mutex_);
296  auto typed_response = std::static_pointer_cast<typename ServiceT::Response>(response);
297  int64_t sequence_number = request_header->sequence_number;
298  // TODO(esteve) this should throw instead since it is not expected to happen in the first place
299  if (this->pending_requests_.count(sequence_number) == 0) {
301  "rclcpp",
302  "Received invalid sequence number. Ignoring...");
303  return;
304  }
305  auto tuple = this->pending_requests_[sequence_number];
306  auto call_promise = std::get<0>(tuple);
307  auto callback = std::get<1>(tuple);
308  auto future = std::get<2>(tuple);
309  this->pending_requests_.erase(sequence_number);
310  // Unlock here to allow the service to be called recursively from one of its callbacks.
311  lock.unlock();
312 
313  call_promise->set_value(typed_response);
314  callback(future);
315  }
316 
319  {
320  return async_send_request(request, [](SharedFuture) {});
321  }
322 
323  template<
324  typename CallbackT,
325  typename std::enable_if<
327  CallbackT,
329  >::value
330  >::type * = nullptr
331  >
333  async_send_request(SharedRequest request, CallbackT && cb)
334  {
335  std::lock_guard<std::mutex> lock(pending_requests_mutex_);
336  int64_t sequence_number;
337  rcl_ret_t ret = rcl_send_request(get_client_handle().get(), request.get(), &sequence_number);
338  if (RCL_RET_OK != ret) {
339  rclcpp::exceptions::throw_from_rcl_error(ret, "failed to send request");
340  }
341 
342  SharedPromise call_promise = std::make_shared<Promise>();
343  SharedFuture f(call_promise->get_future());
344  pending_requests_[sequence_number] =
345  std::make_tuple(call_promise, std::forward<CallbackType>(cb), f);
346  return f;
347  }
348 
349  template<
350  typename CallbackT,
351  typename std::enable_if<
353  CallbackT,
355  >::value
356  >::type * = nullptr
357  >
359  async_send_request(SharedRequest request, CallbackT && cb)
360  {
361  SharedPromiseWithRequest promise = std::make_shared<PromiseWithRequest>();
362  SharedFutureWithRequest future_with_request(promise->get_future());
363 
364  auto wrapping_cb = [future_with_request, promise, request,
365  cb = std::forward<CallbackWithRequestType>(cb)](SharedFuture future) {
366  auto response = future.get();
367  promise->set_value(std::make_pair(request, response));
368  cb(future_with_request);
369  };
370 
371  async_send_request(request, wrapping_cb);
372 
373  return future_with_request;
374  }
375 
376 private:
378 
380  std::mutex pending_requests_mutex_;
381 };
382 
383 } // namespace rclcpp
384 
385 #endif // RCLCPP__CLIENT_HPP_
rclcpp::Client::create_request_header
std::shared_ptr< rmw_request_id_t > create_request_header() override
Create a shared pointer with a rmw_request_id_t.
Definition: client.hpp:278
rcl_node_t
rcl_client_options_t
std::shared_future
node_graph_interface.hpp
rcl_node_get_name
const char * rcl_node_get_name(const rcl_node_t *node)
std::make_tuple
T make_tuple(T... args)
RCL_RET_SERVICE_NAME_INVALID
#define RCL_RET_SERVICE_NAME_INVALID
exceptions.hpp
std::shared_ptr< rcl_client_t >
rcl_node_get_namespace
const char * rcl_node_get_namespace(const rcl_node_t *node)
RCLCPP_DISABLE_COPY
#define RCLCPP_DISABLE_COPY(...)
Definition: macros.hpp:26
rclcpp::ClientBase::ClientBase
ClientBase(rclcpp::node_interfaces::NodeBaseInterface *node_base, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph)
rclcpp::ClientBase::handle_response
virtual void handle_response(std::shared_ptr< rmw_request_id_t > request_header, std::shared_ptr< void > response)=0
rmw.h
rcl_ret_t
rmw_ret_t rcl_ret_t
rclcpp::Client::~Client
virtual ~Client()
Definition: client.hpp:240
wait.h
error_handling.h
std::promise
std::chrono::duration
rclcpp::ClientBase::in_use_by_wait_set_
std::atomic< bool > in_use_by_wait_set_
Definition: client.hpp:174
rclcpp::ClientBase::get_client_handle
std::shared_ptr< rcl_client_t > get_client_handle()
Return the rcl_client_t client handle in a std::shared_ptr.
std::shared_ptr::get
T get(T... args)
std::lock_guard
client.h
std::function
logging_macros.h
rclcpp::ClientBase::node_handle_
std::shared_ptr< rcl_node_t > node_handle_
Definition: client.hpp:169
rclcpp
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
RCLCPP_PUBLIC
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
rclcpp::Client::async_send_request
SharedFuture async_send_request(SharedRequest request)
Definition: client.hpp:318
rclcpp::ClientBase::create_response
virtual std::shared_ptr< void > create_response()=0
rclcpp::node_interfaces::NodeBaseInterface
Pure virtual interface class for the NodeBase part of the Node API.
Definition: node_base_interface.hpp:36
rclcpp::Client::CallbackWithRequestType
std::function< void(SharedFutureWithRequest)> CallbackWithRequestType
Definition: client.hpp:194
RCLCPP_SMART_PTR_DEFINITIONS
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
rclcpp::Client::CallbackType
std::function< void(SharedFuture)> CallbackType
Definition: client.hpp:193
macros.hpp
rclcpp::ClientBase::~ClientBase
virtual ~ClientBase()
rcl_send_request
rcl_ret_t rcl_send_request(const rcl_client_t *client, const void *ros_request, int64_t *sequence_number)
rclcpp::Client::handle_response
void handle_response(std::shared_ptr< rmw_request_id_t > request_header, std::shared_ptr< void > response) override
Handle a server response.
Definition: client.hpp:291
RCUTILS_LOG_ERROR_NAMED
#define RCUTILS_LOG_ERROR_NAMED(name,...)
rclcpp::expand_topic_or_service_name
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.
std::enable_if
rclcpp::Client::async_send_request
SharedFutureWithRequest async_send_request(SharedRequest request, CallbackT &&cb)
Definition: client.hpp:359
rclcpp::ClientBase
Definition: client.hpp:53
rclcpp::ClientBase::create_request_header
virtual std::shared_ptr< rmw_request_id_t > create_request_header()=0
rclcpp::ClientBase::client_handle_
std::shared_ptr< rcl_client_t > client_handle_
Definition: client.hpp:172
rcl_client_init
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)
std::unique_lock
rclcpp::Client::create_response
std::shared_ptr< void > create_response() override
Create a shared pointer with the response type.
Definition: client.hpp:268
expand_topic_or_service_name.hpp
rmw_request_id_t
rclcpp::ClientBase::service_is_ready
bool service_is_ready() const
Return if the service is ready.
std::atomic< bool >
std::map
rclcpp::function_traits::same_arguments
Definition: function_traits.hpp:159
function_traits.hpp
rclcpp::ClientBase::exchange_in_use_by_wait_set_state
bool exchange_in_use_by_wait_set_state(bool in_use_state)
Exchange the "in use by wait set" state for this client.
rclcpp::Client
Definition: client.hpp:178
type_support_decl.hpp
visibility_control.hpp
std
rclcpp::ClientBase::get_service_name
const char * get_service_name() const
Return the name of the service.
rclcpp::Client::SharedFutureWithRequest
std::shared_future< std::pair< SharedRequest, SharedResponse > > SharedFutureWithRequest
Definition: client.hpp:191
rclcpp::ClientBase::wait_for_service
bool wait_for_service(std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Wait for a service to be ready.
Definition: client.hpp:126
std::mutex
RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE
#define RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(...)
Definition: macros.hpp:51
rclcpp::exceptions::throw_from_rcl_error
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::make_pair
T make_pair(T... args)
rclcpp::ClientBase::wait_for_service_nanoseconds
bool wait_for_service_nanoseconds(std::chrono::nanoseconds timeout)
rclcpp::Client::SharedFuture
std::shared_future< SharedResponse > SharedFuture
Definition: client.hpp:190
rclcpp::ClientBase::take_type_erased_response
bool take_type_erased_response(void *response_out, rmw_request_id_t &request_header_out)
Take the next response for this client as a type erased pointer.
rclcpp::Client< rcl_interfaces::srv::GetParameters >::SharedResponse
typename rcl_interfaces::srv::GetParameters ::Response::SharedPtr SharedResponse
Definition: client.hpp:182
rclcpp::Client< rcl_interfaces::srv::GetParameters >::SharedRequest
typename rcl_interfaces::srv::GetParameters ::Request::SharedPtr SharedRequest
Definition: client.hpp:181
rclcpp::ClientBase::get_rcl_node_handle
rcl_node_t * get_rcl_node_handle()
RCL_RET_OK
#define RCL_RET_OK
rclcpp::Client::async_send_request
SharedFuture async_send_request(SharedRequest request, CallbackT &&cb)
Definition: client.hpp:333
rclcpp::ClientBase::node_graph_
rclcpp::node_interfaces::NodeGraphInterface::WeakPtr node_graph_
Definition: client.hpp:168
utilities.hpp
rclcpp::Client::take_response
bool take_response(typename ServiceT::Response &response_out, rmw_request_id_t &request_header_out)
Take the next response for this client.
Definition: client.hpp:258
rclcpp::ClientBase::context_
std::shared_ptr< rclcpp::Context > context_
Definition: client.hpp:170