ROS 2 rclcpp + rcl - jazzy  jazzy
ROS 2 C++ Client Library with ROS Client Library
client.hpp
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 <functional>
20 #include <future>
21 #include <memory>
22 #include <mutex>
23 #include <optional>
24 #include <sstream>
25 #include <string>
26 #include <tuple>
27 #include <unordered_map>
28 #include <utility>
29 #include <variant>
30 #include <vector>
31 
32 #include "rcl/client.h"
33 #include "rcl/error_handling.h"
34 #include "rcl/event_callback.h"
35 #include "rcl/service_introspection.h"
36 #include "rcl/wait.h"
37 
38 #include "rclcpp/clock.hpp"
39 #include "rclcpp/detail/cpp_callback_trampoline.hpp"
40 #include "rclcpp/exceptions.hpp"
41 #include "rclcpp/expand_topic_or_service_name.hpp"
42 #include "rclcpp/function_traits.hpp"
43 #include "rclcpp/logging.hpp"
44 #include "rclcpp/macros.hpp"
45 #include "rclcpp/node_interfaces/node_graph_interface.hpp"
46 #include "rclcpp/qos.hpp"
47 #include "rclcpp/type_support_decl.hpp"
48 #include "rclcpp/utilities.hpp"
49 #include "rclcpp/visibility_control.hpp"
50 
51 #include "rmw/error_handling.h"
52 #include "rmw/impl/cpp/demangle.hpp"
53 #include "rmw/rmw.h"
54 
55 namespace rclcpp
56 {
57 
58 namespace detail
59 {
60 template<typename FutureT>
62 {
63  FutureT future;
64  int64_t request_id;
65 
66  FutureAndRequestId(FutureT impl, int64_t req_id)
67  : future(std::move(impl)), request_id(req_id)
68  {}
69 
71  operator FutureT &() {return this->future;}
72 
74 
78  [[deprecated("FutureAndRequestId: use .future instead of an implicit conversion")]]
79  operator FutureT() {return this->future;}
80 
81  // delegate future like methods in the std::future impl_
82 
84  auto get() {return this->future.get();}
86  bool valid() const noexcept {return this->future.valid();}
88  void wait() const {return this->future.wait();}
90  template<class Rep, class Period>
91  std::future_status wait_for(
92  const std::chrono::duration<Rep, Period> & timeout_duration) const
93  {
94  return this->future.wait_for(timeout_duration);
95  }
97  template<class Clock, class Duration>
98  std::future_status wait_until(
99  const std::chrono::time_point<Clock, Duration> & timeout_time) const
100  {
101  return this->future.wait_until(timeout_time);
102  }
103 
104  // Rule of five, we could use the rule of zero here, but better be explicit as some of the
105  // methods are deleted.
106 
108  FutureAndRequestId(FutureAndRequestId && other) noexcept = default;
110  FutureAndRequestId(const FutureAndRequestId & other) = delete;
112  FutureAndRequestId & operator=(FutureAndRequestId && other) noexcept = default;
116  ~FutureAndRequestId() = default;
117 };
118 
119 template<typename PendingRequestsT, typename AllocatorT = std::allocator<int64_t>>
120 size_t
121 prune_requests_older_than_impl(
122  PendingRequestsT & pending_requests,
123  std::mutex & pending_requests_mutex,
124  std::chrono::time_point<std::chrono::system_clock> time_point,
125  std::vector<int64_t, AllocatorT> * pruned_requests = nullptr)
126 {
127  std::lock_guard guard(pending_requests_mutex);
128  auto old_size = pending_requests.size();
129  for (auto it = pending_requests.begin(), last = pending_requests.end(); it != last; ) {
130  if (it->second.first < time_point) {
131  if (pruned_requests) {
132  pruned_requests->push_back(it->first);
133  }
134  it = pending_requests.erase(it);
135  } else {
136  ++it;
137  }
138  }
139  return old_size - pending_requests.size();
140 }
141 } // namespace detail
142 
143 namespace node_interfaces
144 {
145 class NodeBaseInterface;
146 } // namespace node_interfaces
147 
149 {
150 public:
151  RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(ClientBase)
152 
153  RCLCPP_PUBLIC
154  ClientBase(
156  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph);
157 
158  RCLCPP_PUBLIC
159  virtual ~ClientBase() = default;
160 
162 
178  RCLCPP_PUBLIC
179  bool
180  take_type_erased_response(void * response_out, rmw_request_id_t & request_header_out);
181 
183 
184  RCLCPP_PUBLIC
185  const char *
186  get_service_name() const;
187 
189 
193  RCLCPP_PUBLIC
194  std::shared_ptr<rcl_client_t>
196 
198 
202  RCLCPP_PUBLIC
203  std::shared_ptr<const rcl_client_t>
204  get_client_handle() const;
205 
207 
210  RCLCPP_PUBLIC
211  bool
212  service_is_ready() const;
213 
215 
219  template<typename RepT = int64_t, typename RatioT = std::milli>
220  bool
222  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
223  {
224  return wait_for_service_nanoseconds(
225  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
226  );
227  }
228 
229  virtual std::shared_ptr<void> create_response() = 0;
230  virtual std::shared_ptr<rmw_request_id_t> create_request_header() = 0;
231  virtual void handle_response(
232  std::shared_ptr<rmw_request_id_t> request_header, std::shared_ptr<void> response) = 0;
233 
235 
244  RCLCPP_PUBLIC
245  bool
246  exchange_in_use_by_wait_set_state(bool in_use_state);
247 
249 
260  RCLCPP_PUBLIC
263 
265 
276  RCLCPP_PUBLIC
279 
281 
306  void
307  set_on_new_response_callback(std::function<void(size_t)> callback)
308  {
309  if (!callback) {
310  throw std::invalid_argument(
311  "The callback passed to set_on_new_response_callback "
312  "is not callable.");
313  }
314 
315  auto new_callback =
316  [callback, this](size_t number_of_responses) {
317  try {
318  callback(number_of_responses);
319  } catch (const std::exception & exception) {
320  RCLCPP_ERROR_STREAM(
321  node_logger_,
322  "rclcpp::ClientBase@" << this <<
323  " caught " << rmw::impl::cpp::demangle(exception) <<
324  " exception in user-provided callback for the 'on new response' callback: " <<
325  exception.what());
326  } catch (...) {
327  RCLCPP_ERROR_STREAM(
328  node_logger_,
329  "rclcpp::ClientBase@" << this <<
330  " caught unhandled exception in user-provided callback " <<
331  "for the 'on new response' callback");
332  }
333  };
334 
335  std::lock_guard<std::recursive_mutex> lock(callback_mutex_);
336 
337  // Set it temporarily to the new callback, while we replace the old one.
338  // This two-step setting, prevents a gap where the old std::function has
339  // been replaced but the middleware hasn't been told about the new one yet.
341  rclcpp::detail::cpp_callback_trampoline<decltype(new_callback), const void *, size_t>,
342  static_cast<const void *>(&new_callback));
343 
344  // Store the std::function to keep it in scope, also overwrites the existing one.
345  on_new_response_callback_ = new_callback;
346 
347  // Set it again, now using the permanent storage.
349  rclcpp::detail::cpp_callback_trampoline<
350  decltype(on_new_response_callback_), const void *, size_t>,
351  static_cast<const void *>(&on_new_response_callback_));
352  }
353 
355  void
357  {
358  std::lock_guard<std::recursive_mutex> lock(callback_mutex_);
359  if (on_new_response_callback_) {
360  set_on_new_response_callback(nullptr, nullptr);
361  on_new_response_callback_ = nullptr;
362  }
363  }
364 
365 protected:
366  RCLCPP_DISABLE_COPY(ClientBase)
367 
368  RCLCPP_PUBLIC
369  bool
370  wait_for_service_nanoseconds(std::chrono::nanoseconds timeout);
371 
372  RCLCPP_PUBLIC
373  rcl_node_t *
374  get_rcl_node_handle();
375 
376  RCLCPP_PUBLIC
377  const rcl_node_t *
378  get_rcl_node_handle() const;
379 
380  RCLCPP_PUBLIC
381  void
382  set_on_new_response_callback(rcl_event_callback_t callback, const void * user_data);
383 
384  rclcpp::node_interfaces::NodeGraphInterface::WeakPtr node_graph_;
385  std::shared_ptr<rcl_node_t> node_handle_;
386  std::shared_ptr<rclcpp::Context> context_;
387  rclcpp::Logger node_logger_;
388 
389  std::recursive_mutex callback_mutex_;
390  // It is important to declare on_new_response_callback_ before
391  // client_handle_, so on destruction the client is
392  // destroyed first. Otherwise, the rmw client callback
393  // would point briefly to a destroyed function.
394  std::function<void(size_t)> on_new_response_callback_{nullptr};
395  // Declare client_handle_ after callback
396  std::shared_ptr<rcl_client_t> client_handle_;
397 
398  std::atomic<bool> in_use_by_wait_set_{false};
399 };
400 
401 template<typename ServiceT>
402 class Client : public ClientBase
403 {
404 public:
405  using Request = typename ServiceT::Request;
406  using Response = typename ServiceT::Response;
407 
408  using SharedRequest = typename ServiceT::Request::SharedPtr;
409  using SharedResponse = typename ServiceT::Response::SharedPtr;
410 
411  using Promise = std::promise<SharedResponse>;
412  using PromiseWithRequest = std::promise<std::pair<SharedRequest, SharedResponse>>;
413 
414  using SharedPromise = std::shared_ptr<Promise>;
415  using SharedPromiseWithRequest = std::shared_ptr<PromiseWithRequest>;
416 
417  using Future = std::future<SharedResponse>;
418  using SharedFuture = std::shared_future<SharedResponse>;
419  using SharedFutureWithRequest = std::shared_future<std::pair<SharedRequest, SharedResponse>>;
420 
421  using CallbackType = std::function<void (SharedFuture)>;
422  using CallbackWithRequestType = std::function<void (SharedFutureWithRequest)>;
423 
424  RCLCPP_SMART_PTR_DEFINITIONS(Client)
425 
426 
435  : detail::FutureAndRequestId<std::future<SharedResponse>>
436  {
438 
440 
444  [[deprecated(
445  "FutureAndRequestId: use .future.share() instead of an implicit conversion")]]
446  operator SharedFuture() {return this->future.share();}
447 
448  // delegate future like methods in the std::future impl_
449 
451  SharedFuture share() noexcept {return this->future.share();}
452  };
453 
455 
463  : detail::FutureAndRequestId<std::shared_future<SharedResponse>>
464  {
466  };
467 
469 
477  : detail::FutureAndRequestId<std::shared_future<std::pair<SharedRequest, SharedResponse>>>
478  {
480  std::shared_future<std::pair<SharedRequest, SharedResponse>>
482  };
483 
485 
497  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph,
498  const std::string & service_name,
499  rcl_client_options_t & client_options)
500  : ClientBase(node_base, node_graph),
501  srv_type_support_handle_(rosidl_typesupport_cpp::get_service_type_support_handle<ServiceT>())
502  {
504  this->get_client_handle().get(),
505  this->get_rcl_node_handle(),
506  srv_type_support_handle_,
507  service_name.c_str(),
508  &client_options);
509  if (ret != RCL_RET_OK) {
510  if (ret == RCL_RET_SERVICE_NAME_INVALID) {
511  auto rcl_node_handle = this->get_rcl_node_handle();
512  // this will throw on any validation problem
513  rcl_reset_error();
515  service_name,
516  rcl_node_get_name(rcl_node_handle),
517  rcl_node_get_namespace(rcl_node_handle),
518  true);
519  }
520  rclcpp::exceptions::throw_from_rcl_error(ret, "could not create client");
521  }
522  }
523 
524  virtual ~Client()
525  {
526  }
527 
529 
541  bool
542  take_response(typename ServiceT::Response & response_out, rmw_request_id_t & request_header_out)
543  {
544  return this->take_type_erased_response(&response_out, request_header_out);
545  }
546 
548 
551  std::shared_ptr<void>
552  create_response() override
553  {
554  return std::shared_ptr<void>(new typename ServiceT::Response());
555  }
556 
558 
561  std::shared_ptr<rmw_request_id_t>
563  {
564  // TODO(wjwwood): This should probably use rmw_request_id's allocator.
565  // (since it is a C type)
566  return std::shared_ptr<rmw_request_id_t>(new rmw_request_id_t);
567  }
568 
570 
574  void
576  std::shared_ptr<rmw_request_id_t> request_header,
577  std::shared_ptr<void> response) override
578  {
579  std::optional<CallbackInfoVariant>
580  optional_pending_request = this->get_and_erase_pending_request(request_header->sequence_number);
581  if (!optional_pending_request) {
582  return;
583  }
584  auto & value = *optional_pending_request;
585  auto typed_response = std::static_pointer_cast<typename ServiceT::Response>(
586  std::move(response));
587  if (std::holds_alternative<Promise>(value)) {
588  auto & promise = std::get<Promise>(value);
589  promise.set_value(std::move(typed_response));
590  } else if (std::holds_alternative<CallbackTypeValueVariant>(value)) {
591  auto & inner = std::get<CallbackTypeValueVariant>(value);
592  const auto & callback = std::get<CallbackType>(inner);
593  auto & promise = std::get<Promise>(inner);
594  auto & future = std::get<SharedFuture>(inner);
595  promise.set_value(std::move(typed_response));
596  callback(std::move(future));
597  } else if (std::holds_alternative<CallbackWithRequestTypeValueVariant>(value)) {
598  auto & inner = std::get<CallbackWithRequestTypeValueVariant>(value);
599  const auto & callback = std::get<CallbackWithRequestType>(inner);
600  auto & promise = std::get<PromiseWithRequest>(inner);
601  auto & future = std::get<SharedFutureWithRequest>(inner);
602  auto & request = std::get<SharedRequest>(inner);
603  promise.set_value(std::make_pair(std::move(request), std::move(typed_response)));
604  callback(std::move(future));
605  }
606  }
607 
609 
636  FutureAndRequestId
637  async_send_request(SharedRequest request)
638  {
639  Promise promise;
640  auto future = promise.get_future();
641  auto req_id = async_send_request_impl(
642  *request,
643  std::move(promise));
644  return FutureAndRequestId(std::move(future), req_id);
645  }
646 
648 
662  template<
663  typename CallbackT,
664  typename std::enable_if<
666  CallbackT,
667  CallbackType
668  >::value
669  >::type * = nullptr
670  >
671  SharedFutureAndRequestId
672  async_send_request(SharedRequest request, CallbackT && cb)
673  {
674  Promise promise;
675  auto shared_future = promise.get_future().share();
676  auto req_id = async_send_request_impl(
677  *request,
678  std::make_tuple(
679  CallbackType{std::forward<CallbackT>(cb)},
680  shared_future,
681  std::move(promise)));
682  return SharedFutureAndRequestId{std::move(shared_future), req_id};
683  }
684 
686 
693  template<
694  typename CallbackT,
695  typename std::enable_if<
697  CallbackT,
698  CallbackWithRequestType
699  >::value
700  >::type * = nullptr
701  >
702  SharedFutureWithRequestAndRequestId
703  async_send_request(SharedRequest request, CallbackT && cb)
704  {
705  PromiseWithRequest promise;
706  auto shared_future = promise.get_future().share();
707  auto req_id = async_send_request_impl(
708  *request,
709  std::make_tuple(
710  CallbackWithRequestType{std::forward<CallbackT>(cb)},
711  request,
712  shared_future,
713  std::move(promise)));
714  return SharedFutureWithRequestAndRequestId{std::move(shared_future), req_id};
715  }
716 
718 
728  bool
729  remove_pending_request(int64_t request_id)
730  {
731  std::lock_guard guard(pending_requests_mutex_);
732  return pending_requests_.erase(request_id) != 0u;
733  }
734 
736 
741  bool
743  {
744  return this->remove_pending_request(future.request_id);
745  }
746 
748 
753  bool
755  {
756  return this->remove_pending_request(future.request_id);
757  }
758 
760 
765  bool
767  {
768  return this->remove_pending_request(future.request_id);
769  }
770 
772 
775  size_t
777  {
778  std::lock_guard guard(pending_requests_mutex_);
779  auto ret = pending_requests_.size();
780  pending_requests_.clear();
781  return ret;
782  }
783 
785 
791  template<typename AllocatorT = std::allocator<int64_t>>
792  size_t
794  std::chrono::time_point<std::chrono::system_clock> time_point,
795  std::vector<int64_t, AllocatorT> * pruned_requests = nullptr)
796  {
797  return detail::prune_requests_older_than_impl(
798  pending_requests_,
799  pending_requests_mutex_,
800  time_point,
801  pruned_requests);
802  }
803 
805 
810  void
812  Clock::SharedPtr clock, const QoS & qos_service_event_pub,
813  rcl_service_introspection_state_t introspection_state)
814  {
816  pub_opts.qos = qos_service_event_pub.get_rmw_qos_profile();
817 
819  client_handle_.get(),
820  node_handle_.get(),
821  clock->get_clock_handle(),
822  srv_type_support_handle_,
823  pub_opts,
824  introspection_state);
825 
826  if (RCL_RET_OK != ret) {
827  rclcpp::exceptions::throw_from_rcl_error(ret, "failed to configure client introspection");
828  }
829  }
830 
831 protected:
832  using CallbackTypeValueVariant = std::tuple<CallbackType, SharedFuture, Promise>;
833  using CallbackWithRequestTypeValueVariant = std::tuple<
834  CallbackWithRequestType, SharedRequest, SharedFutureWithRequest, PromiseWithRequest>;
835 
836  using CallbackInfoVariant = std::variant<
837  std::promise<SharedResponse>,
838  CallbackTypeValueVariant,
839  CallbackWithRequestTypeValueVariant>;
840 
841  int64_t
842  async_send_request_impl(const Request & request, CallbackInfoVariant value)
843  {
844  int64_t sequence_number;
845  std::lock_guard<std::mutex> lock(pending_requests_mutex_);
846  rcl_ret_t ret = rcl_send_request(get_client_handle().get(), &request, &sequence_number);
847  if (RCL_RET_OK != ret) {
848  rclcpp::exceptions::throw_from_rcl_error(ret, "failed to send request");
849  }
850  pending_requests_.try_emplace(
851  sequence_number,
852  std::make_pair(std::chrono::system_clock::now(), std::move(value)));
853  return sequence_number;
854  }
855 
856  std::optional<CallbackInfoVariant>
857  get_and_erase_pending_request(int64_t request_number)
858  {
859  std::unique_lock<std::mutex> lock(pending_requests_mutex_);
860  auto it = this->pending_requests_.find(request_number);
861  if (it == this->pending_requests_.end()) {
862  RCUTILS_LOG_DEBUG_NAMED(
863  "rclcpp",
864  "Received invalid sequence number. Ignoring...");
865  return std::nullopt;
866  }
867  std::optional<CallbackInfoVariant> value = std::move(it->second.second);
868  this->pending_requests_.erase(request_number);
869  return value;
870  }
871 
872  RCLCPP_DISABLE_COPY(Client)
873 
874  std::unordered_map<
875  int64_t,
876  std::pair<
877  std::chrono::time_point<std::chrono::system_clock>,
878  CallbackInfoVariant>>
879  pending_requests_;
880  std::mutex pending_requests_mutex_;
881 
882 private:
883  const rosidl_service_type_support_t * srv_type_support_handle_;
884 };
885 
886 } // namespace rclcpp
887 
888 #endif // RCLCPP__CLIENT_HPP_
RCLCPP_PUBLIC bool exchange_in_use_by_wait_set_state(bool in_use_state)
Exchange the "in use by wait set" state for this client.
Definition: client.cpp:194
RCLCPP_PUBLIC rclcpp::QoS get_request_publisher_actual_qos() const
Get the actual request publsher QoS settings, after the defaults have been determined.
Definition: client.cpp:200
RCLCPP_PUBLIC std::shared_ptr< rcl_client_t > get_client_handle()
Return the rcl_client_t client handle in a std::shared_ptr.
Definition: client.cpp:92
void set_on_new_response_callback(std::function< void(size_t)> callback)
Set a callback to be called when each new response is received.
Definition: client.hpp:307
RCLCPP_PUBLIC 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.
Definition: client.cpp:71
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:221
RCLCPP_PUBLIC const char * get_service_name() const
Return the name of the service.
Definition: client.cpp:86
void clear_on_new_response_callback()
Unset the callback registered for new responses, if any.
Definition: client.hpp:356
RCLCPP_PUBLIC rclcpp::QoS get_response_subscription_actual_qos() const
Get the actual response subscription QoS settings, after the defaults have been determined.
Definition: client.cpp:219
RCLCPP_PUBLIC bool service_is_ready() const
Return if the service is ready.
Definition: client.cpp:104
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:542
std::shared_ptr< rmw_request_id_t > create_request_header() override
Create a shared pointer with a rmw_request_id_t.
Definition: client.hpp:562
bool remove_pending_request(int64_t request_id)
Cleanup a pending request.
Definition: client.hpp:729
void configure_introspection(Clock::SharedPtr clock, const QoS &qos_service_event_pub, rcl_service_introspection_state_t introspection_state)
Configure client introspection.
Definition: client.hpp:811
std::shared_ptr< void > create_response() override
Create a shared pointer with the response type.
Definition: client.hpp:552
size_t prune_requests_older_than(std::chrono::time_point< std::chrono::system_clock > time_point, std::vector< int64_t, AllocatorT > *pruned_requests=nullptr)
Clean all pending requests older than a time_point.
Definition: client.hpp:793
SharedFutureWithRequestAndRequestId async_send_request(SharedRequest request, CallbackT &&cb)
Send a request to the service server and schedule a callback in the executor.
Definition: client.hpp:703
SharedFutureAndRequestId async_send_request(SharedRequest request, CallbackT &&cb)
Send a request to the service server and schedule a callback in the executor.
Definition: client.hpp:672
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:575
FutureAndRequestId async_send_request(SharedRequest request)
Send a request to the service server.
Definition: client.hpp:637
size_t prune_pending_requests()
Clean all pending requests.
Definition: client.hpp:776
bool remove_pending_request(const SharedFutureAndRequestId &future)
Cleanup a pending request.
Definition: client.hpp:754
bool remove_pending_request(const SharedFutureWithRequestAndRequestId &future)
Cleanup a pending request.
Definition: client.hpp:766
Client(rclcpp::node_interfaces::NodeBaseInterface *node_base, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph, const std::string &service_name, rcl_client_options_t &client_options)
Default constructor.
Definition: client.hpp:495
bool remove_pending_request(const FutureAndRequestId &future)
Cleanup a pending request.
Definition: client.hpp:742
Encapsulation of Quality of Service settings.
Definition: qos.hpp:116
rmw_qos_profile_t & get_rmw_qos_profile()
Return the rmw qos profile.
Definition: qos.cpp:102
Pure virtual interface class for the NodeBase part of the Node API.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_client_configure_service_introspection(rcl_client_t *client, rcl_node_t *node, rcl_clock_t *clock, const rosidl_service_type_support_t *type_support, const rcl_publisher_options_t publisher_options, rcl_service_introspection_state_t introspection_state)
Configures service introspection features for the client.
Definition: client.c:465
RCL_PUBLIC RCL_WARN_UNUSED 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)
Initialize a rcl client.
Definition: client.c:86
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_send_request(const rcl_client_t *client, const void *ros_request, int64_t *sequence_number)
Send a ROS request using a client.
Definition: client.c:317
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
RCLCPP_PUBLIC 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.
RCL_PUBLIC RCL_WARN_UNUSED const char * rcl_node_get_name(const rcl_node_t *node)
Return the name of the node.
Definition: node.c:411
RCL_PUBLIC RCL_WARN_UNUSED const char * rcl_node_get_namespace(const rcl_node_t *node)
Return the namespace of the node.
Definition: node.c:420
RCL_PUBLIC RCL_WARN_UNUSED rcl_publisher_options_t rcl_publisher_get_default_options(void)
Return the default publisher options in a rcl_publisher_options_t.
Definition: publisher.c:219
Options available for a rcl_client_t.
Definition: client.h:50
Structure which encapsulates a ROS Node.
Definition: node.h:45
Options available for a rcl publisher.
Definition: publisher.h:44
rmw_qos_profile_t qos
Middleware quality of service settings for the publisher.
Definition: publisher.h:46
A convenient Client::Future and request id pair.
Definition: client.hpp:436
SharedFuture share() noexcept
See std::future::share().
Definition: client.hpp:451
A convenient Client::SharedFuture and request id pair.
Definition: client.hpp:464
A convenient Client::SharedFutureWithRequest and request id pair.
Definition: client.hpp:478
std::future_status wait_for(const std::chrono::duration< Rep, Period > &timeout_duration) const
See std::future::wait_for().
Definition: client.hpp:91
std::future_status wait_until(const std::chrono::time_point< Clock, Duration > &timeout_time) const
See std::future::wait_until().
Definition: client.hpp:98
FutureAndRequestId & operator=(FutureAndRequestId &&other) noexcept=default
Move assignment.
FutureAndRequestId & operator=(const FutureAndRequestId &other)=delete
Deleted copy assignment, each instance is a unique owner of the future.
FutureAndRequestId(const FutureAndRequestId &other)=delete
Deleted copy constructor, each instance is a unique owner of the future.
void wait() const
See std::future::wait().
Definition: client.hpp:88
FutureAndRequestId(FutureAndRequestId &&other) noexcept=default
Move constructor.
~FutureAndRequestId()=default
Destructor.
auto get()
See std::future::get().
Definition: client.hpp:84
bool valid() const noexcept
See std::future::valid().
Definition: client.hpp:86
#define RCL_RET_SERVICE_NAME_INVALID
Service name (same as topic name) does not pass validation.
Definition: types.h:49
#define RCL_RET_OK
Success return code.
Definition: types.h:27
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.
Definition: types.h:24