ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
service.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__SERVICE_HPP_
16 #define RCLCPP__SERVICE_HPP_
17 
18 #include <atomic>
19 #include <functional>
20 #include <iostream>
21 #include <memory>
22 #include <mutex>
23 #include <sstream>
24 #include <string>
25 
26 #include "rcl/error_handling.h"
27 #include "rcl/event_callback.h"
28 #include "rcl/service.h"
29 
30 #include "rmw/error_handling.h"
31 #include "rmw/impl/cpp/demangle.hpp"
32 #include "rmw/rmw.h"
33 
34 #include "tracetools/tracetools.h"
35 
36 #include "rclcpp/any_service_callback.hpp"
37 #include "rclcpp/detail/cpp_callback_trampoline.hpp"
38 #include "rclcpp/exceptions.hpp"
39 #include "rclcpp/expand_topic_or_service_name.hpp"
40 #include "rclcpp/logging.hpp"
41 #include "rclcpp/macros.hpp"
42 #include "rclcpp/qos.hpp"
43 #include "rclcpp/type_support_decl.hpp"
44 #include "rclcpp/visibility_control.hpp"
45 
46 namespace rclcpp
47 {
48 
50 {
51 public:
52  RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(ServiceBase)
53 
54  RCLCPP_PUBLIC
55  explicit ServiceBase(std::shared_ptr<rcl_node_t> node_handle);
56 
57  RCLCPP_PUBLIC
58  virtual ~ServiceBase();
59 
61 
62  RCLCPP_PUBLIC
63  const char *
65 
67 
71  RCLCPP_PUBLIC
72  std::shared_ptr<rcl_service_t>
74 
76 
80  RCLCPP_PUBLIC
81  std::shared_ptr<const rcl_service_t>
82  get_service_handle() const;
83 
85 
99  RCLCPP_PUBLIC
100  bool
101  take_type_erased_request(void * request_out, rmw_request_id_t & request_id_out);
102 
103  virtual
104  std::shared_ptr<void>
105  create_request() = 0;
106 
107  virtual
108  std::shared_ptr<rmw_request_id_t>
109  create_request_header() = 0;
110 
111  virtual
112  void
113  handle_request(
114  std::shared_ptr<rmw_request_id_t> request_header,
115  std::shared_ptr<void> request) = 0;
116 
118 
127  RCLCPP_PUBLIC
128  bool
129  exchange_in_use_by_wait_set_state(bool in_use_state);
130 
132 
143  RCLCPP_PUBLIC
146 
148 
159  RCLCPP_PUBLIC
162 
164 
190  void
191  set_on_new_request_callback(std::function<void(size_t)> callback)
192  {
193  if (!callback) {
194  throw std::invalid_argument(
195  "The callback passed to set_on_new_request_callback "
196  "is not callable.");
197  }
198 
199  auto new_callback =
200  [callback, this](size_t number_of_requests) {
201  try {
202  callback(number_of_requests);
203  } catch (const std::exception & exception) {
204  RCLCPP_ERROR_STREAM(
205  node_logger_,
206  "rclcpp::ServiceBase@" << this <<
207  " caught " << rmw::impl::cpp::demangle(exception) <<
208  " exception in user-provided callback for the 'on new request' callback: " <<
209  exception.what());
210  } catch (...) {
211  RCLCPP_ERROR_STREAM(
212  node_logger_,
213  "rclcpp::ServiceBase@" << this <<
214  " caught unhandled exception in user-provided callback " <<
215  "for the 'on new request' callback");
216  }
217  };
218 
219  std::lock_guard<std::recursive_mutex> lock(callback_mutex_);
220 
221  // Set it temporarily to the new callback, while we replace the old one.
222  // This two-step setting, prevents a gap where the old std::function has
223  // been replaced but the middleware hasn't been told about the new one yet.
225  rclcpp::detail::cpp_callback_trampoline<const void *, size_t>,
226  static_cast<const void *>(&new_callback));
227 
228  // Store the std::function to keep it in scope, also overwrites the existing one.
229  on_new_request_callback_ = new_callback;
230 
231  // Set it again, now using the permanent storage.
233  rclcpp::detail::cpp_callback_trampoline<const void *, size_t>,
234  static_cast<const void *>(&on_new_request_callback_));
235  }
236 
238  void
240  {
241  std::lock_guard<std::recursive_mutex> lock(callback_mutex_);
242  if (on_new_request_callback_) {
243  set_on_new_request_callback(nullptr, nullptr);
244  on_new_request_callback_ = nullptr;
245  }
246  }
247 
248 protected:
249  RCLCPP_DISABLE_COPY(ServiceBase)
250 
251  RCLCPP_PUBLIC
252  rcl_node_t *
253  get_rcl_node_handle();
254 
255  RCLCPP_PUBLIC
256  const rcl_node_t *
257  get_rcl_node_handle() const;
258 
259  RCLCPP_PUBLIC
260  void
261  set_on_new_request_callback(rcl_event_callback_t callback, const void * user_data);
262 
263  std::shared_ptr<rcl_node_t> node_handle_;
264 
265  std::shared_ptr<rcl_service_t> service_handle_;
266  bool owns_rcl_handle_ = true;
267 
268  rclcpp::Logger node_logger_;
269 
270  std::atomic<bool> in_use_by_wait_set_{false};
271 
272  std::recursive_mutex callback_mutex_;
273  std::function<void(size_t)> on_new_request_callback_{nullptr};
274 };
275 
276 template<typename ServiceT>
277 class Service
278  : public ServiceBase,
279  public std::enable_shared_from_this<Service<ServiceT>>
280 {
281 public:
282  using CallbackType = std::function<
283  void (
284  const std::shared_ptr<typename ServiceT::Request>,
285  std::shared_ptr<typename ServiceT::Response>)>;
286 
287  using CallbackWithHeaderType = std::function<
288  void (
289  const std::shared_ptr<rmw_request_id_t>,
290  const std::shared_ptr<typename ServiceT::Request>,
291  std::shared_ptr<typename ServiceT::Response>)>;
292  RCLCPP_SMART_PTR_DEFINITIONS(Service)
293 
294 
306  std::shared_ptr<rcl_node_t> node_handle,
307  const std::string & service_name,
308  AnyServiceCallback<ServiceT> any_callback,
309  rcl_service_options_t & service_options)
310  : ServiceBase(node_handle), any_callback_(any_callback)
311  {
312  using rosidl_typesupport_cpp::get_service_type_support_handle;
313  auto service_type_support_handle = get_service_type_support_handle<ServiceT>();
314 
315  // rcl does the static memory allocation here
316  service_handle_ = std::shared_ptr<rcl_service_t>(
317  new rcl_service_t, [handle = node_handle_, service_name](rcl_service_t * service)
318  {
319  if (rcl_service_fini(service, handle.get()) != RCL_RET_OK) {
320  RCLCPP_ERROR(
321  rclcpp::get_node_logger(handle.get()).get_child("rclcpp"),
322  "Error in destruction of rcl service handle: %s",
323  rcl_get_error_string().str);
324  rcl_reset_error();
325  }
326  delete service;
327  });
328  *service_handle_.get() = rcl_get_zero_initialized_service();
329 
331  service_handle_.get(),
332  node_handle.get(),
333  service_type_support_handle,
334  service_name.c_str(),
335  &service_options);
336  if (ret != RCL_RET_OK) {
337  if (ret == RCL_RET_SERVICE_NAME_INVALID) {
338  auto rcl_node_handle = get_rcl_node_handle();
339  // this will throw on any validation problem
340  rcl_reset_error();
342  service_name,
343  rcl_node_get_name(rcl_node_handle),
344  rcl_node_get_namespace(rcl_node_handle),
345  true);
346  }
347 
348  rclcpp::exceptions::throw_from_rcl_error(ret, "could not create service");
349  }
350  TRACEPOINT(
351  rclcpp_service_callback_added,
352  static_cast<const void *>(get_service_handle().get()),
353  static_cast<const void *>(&any_callback_));
354 #ifndef TRACETOOLS_DISABLED
355  any_callback_.register_callback_for_tracing();
356 #endif
357  }
358 
360 
370  std::shared_ptr<rcl_node_t> node_handle,
371  std::shared_ptr<rcl_service_t> service_handle,
372  AnyServiceCallback<ServiceT> any_callback)
373  : ServiceBase(node_handle),
374  any_callback_(any_callback)
375  {
376  // check if service handle was initialized
377  if (!rcl_service_is_valid(service_handle.get())) {
378  // *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
379  throw std::runtime_error(
380  std::string("rcl_service_t in constructor argument must be initialized beforehand."));
381  // *INDENT-ON*
382  }
383 
384  service_handle_ = service_handle;
385  TRACEPOINT(
386  rclcpp_service_callback_added,
387  static_cast<const void *>(get_service_handle().get()),
388  static_cast<const void *>(&any_callback_));
389 #ifndef TRACETOOLS_DISABLED
390  any_callback_.register_callback_for_tracing();
391 #endif
392  }
393 
395 
405  std::shared_ptr<rcl_node_t> node_handle,
406  rcl_service_t * service_handle,
407  AnyServiceCallback<ServiceT> any_callback)
408  : ServiceBase(node_handle),
409  any_callback_(any_callback)
410  {
411  // check if service handle was initialized
412  if (!rcl_service_is_valid(service_handle)) {
413  // *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
414  throw std::runtime_error(
415  std::string("rcl_service_t in constructor argument must be initialized beforehand."));
416  // *INDENT-ON*
417  }
418 
419  // In this case, rcl owns the service handle memory
420  service_handle_ = std::shared_ptr<rcl_service_t>(new rcl_service_t);
421  service_handle_->impl = service_handle->impl;
422  TRACEPOINT(
423  rclcpp_service_callback_added,
424  static_cast<const void *>(get_service_handle().get()),
425  static_cast<const void *>(&any_callback_));
426 #ifndef TRACETOOLS_DISABLED
427  any_callback_.register_callback_for_tracing();
428 #endif
429  }
430 
431  Service() = delete;
432 
433  virtual ~Service()
434  {
435  }
436 
438 
449  bool
450  take_request(typename ServiceT::Request & request_out, rmw_request_id_t & request_id_out)
451  {
452  return this->take_type_erased_request(&request_out, request_id_out);
453  }
454 
455  std::shared_ptr<void>
456  create_request() override
457  {
458  return std::make_shared<typename ServiceT::Request>();
459  }
460 
461  std::shared_ptr<rmw_request_id_t>
462  create_request_header() override
463  {
464  return std::make_shared<rmw_request_id_t>();
465  }
466 
467  void
468  handle_request(
469  std::shared_ptr<rmw_request_id_t> request_header,
470  std::shared_ptr<void> request) override
471  {
472  auto typed_request = std::static_pointer_cast<typename ServiceT::Request>(request);
473  auto response = any_callback_.dispatch(this->shared_from_this(), request_header, typed_request);
474  if (response) {
475  send_response(*request_header, *response);
476  }
477  }
478 
479  void
480  send_response(rmw_request_id_t & req_id, typename ServiceT::Response & response)
481  {
482  rcl_ret_t ret = rcl_send_response(get_service_handle().get(), &req_id, &response);
483 
484  if (ret == RCL_RET_TIMEOUT) {
485  RCLCPP_WARN(
486  node_logger_.get_child("rclcpp"),
487  "failed to send response to %s (timeout): %s",
488  this->get_service_name(), rcl_get_error_string().str);
489  rcl_reset_error();
490  return;
491  }
492  if (ret != RCL_RET_OK) {
493  rclcpp::exceptions::throw_from_rcl_error(ret, "failed to send response");
494  }
495  }
496 
497 private:
498  RCLCPP_DISABLE_COPY(Service)
499 
500  AnyServiceCallback<ServiceT> any_callback_;
501 };
502 
503 } // namespace rclcpp
504 
505 #endif // RCLCPP__SERVICE_HPP_
RCLCPP_PUBLIC Logger get_child(const std::string &suffix)
Return a logger that is a descendant of this logger.
Definition: logger.hpp:160
Encapsulation of Quality of Service settings.
Definition: qos.hpp:111
RCLCPP_PUBLIC bool exchange_in_use_by_wait_set_state(bool in_use_state)
Exchange the "in use by wait set" state for this service.
Definition: service.cpp:86
RCLCPP_PUBLIC rclcpp::QoS get_request_subscription_actual_qos() const
Get the actual request subscription QoS settings, after the defaults have been determined.
Definition: service.cpp:111
RCLCPP_PUBLIC rclcpp::QoS get_response_publisher_actual_qos() const
Get the actual response publisher QoS settings, after the defaults have been determined.
Definition: service.cpp:92
void set_on_new_request_callback(std::function< void(size_t)> callback)
Set a callback to be called when each new request is received.
Definition: service.hpp:191
void clear_on_new_request_callback()
Unset the callback registered for new requests, if any.
Definition: service.hpp:239
RCLCPP_PUBLIC std::shared_ptr< rcl_service_t > get_service_handle()
Return the rcl_service_t service handle in a std::shared_ptr.
Definition: service.cpp:62
RCLCPP_PUBLIC bool take_type_erased_request(void *request_out, rmw_request_id_t &request_id_out)
Take the next request from the service as a type erased pointer.
Definition: service.cpp:41
RCLCPP_PUBLIC const char * get_service_name()
Return the name of the service.
Definition: service.cpp:56
bool take_request(typename ServiceT::Request &request_out, rmw_request_id_t &request_id_out)
Take the next request from the service.
Definition: service.hpp:450
Service(std::shared_ptr< rcl_node_t > node_handle, std::shared_ptr< rcl_service_t > service_handle, AnyServiceCallback< ServiceT > any_callback)
Default constructor.
Definition: service.hpp:369
Service(std::shared_ptr< rcl_node_t > node_handle, rcl_service_t *service_handle, AnyServiceCallback< ServiceT > any_callback)
Default constructor.
Definition: service.hpp:404
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:435
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:444
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_service_init(rcl_service_t *service, const rcl_node_t *node, const rosidl_service_type_support_t *type_support, const char *service_name, const rcl_service_options_t *options)
Initialize a rcl service.
Definition: service.c:49
RCL_PUBLIC bool rcl_service_is_valid(const rcl_service_t *service)
Check that the service is valid.
Definition: service.c:324
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_service_fini(rcl_service_t *service, rcl_node_t *node)
Finalize a rcl_service_t.
Definition: service.c:176
RCL_PUBLIC RCL_WARN_UNUSED rcl_service_t rcl_get_zero_initialized_service(void)
Return a rcl_service_t struct with members set to NULL.
Definition: service.c:42
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_send_response(const rcl_service_t *service, rmw_request_id_t *response_header, void *ros_response)
Send a ROS response to a client using a service.
Definition: service.c:297
Structure which encapsulates a ROS Node.
Definition: node.h:42
Options available for a rcl service.
Definition: service.h:44
Structure which encapsulates a ROS Service.
Definition: service.h:37
rcl_service_impl_t * impl
Pointer to the service implementation.
Definition: service.h:39
#define RCL_RET_SERVICE_NAME_INVALID
Service name (same as topic name) does not pass validation.
Definition: types.h:48
#define RCL_RET_OK
Success return code.
Definition: types.h:26
#define RCL_RET_TIMEOUT
Timeout occurred return code.
Definition: types.h:30
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.
Definition: types.h:23