ROS 2 rclcpp + rcl - rolling  rolling-a919a6e5
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 #include "rcl/service_introspection.h"
30 
31 #include "rmw/error_handling.h"
32 #include "rmw/impl/cpp/demangle.hpp"
33 #include "rmw/rmw.h"
34 
35 #include "tracetools/tracetools.h"
36 
37 #include "rclcpp/any_service_callback.hpp"
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/logging.hpp"
43 #include "rclcpp/macros.hpp"
44 #include "rclcpp/qos.hpp"
45 #include "rclcpp/type_support_decl.hpp"
46 #include "rclcpp/visibility_control.hpp"
47 
48 namespace rclcpp
49 {
50 
52 {
53 public:
54  RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(ServiceBase)
55 
56  RCLCPP_PUBLIC
57  explicit ServiceBase(std::shared_ptr<rcl_node_t> node_handle);
58 
59  RCLCPP_PUBLIC
60  virtual ~ServiceBase() = default;
61 
63 
64  RCLCPP_PUBLIC
65  const char *
67 
69 
73  RCLCPP_PUBLIC
74  std::shared_ptr<rcl_service_t>
76 
78 
82  RCLCPP_PUBLIC
83  std::shared_ptr<const rcl_service_t>
84  get_service_handle() const;
85 
87 
101  RCLCPP_PUBLIC
102  bool
103  take_type_erased_request(void * request_out, rmw_request_id_t & request_id_out);
104 
105  virtual
106  std::shared_ptr<void>
107  create_request() = 0;
108 
109  virtual
110  std::shared_ptr<rmw_request_id_t>
111  create_request_header() = 0;
112 
113  virtual
114  void
115  handle_request(
116  std::shared_ptr<rmw_request_id_t> request_header,
117  std::shared_ptr<void> request) = 0;
118 
120 
129  RCLCPP_PUBLIC
130  bool
131  exchange_in_use_by_wait_set_state(bool in_use_state);
132 
134 
145  RCLCPP_PUBLIC
148 
150 
161  RCLCPP_PUBLIC
164 
166 
192  void
193  set_on_new_request_callback(std::function<void(size_t)> callback)
194  {
195  if (!callback) {
196  throw std::invalid_argument(
197  "The callback passed to set_on_new_request_callback "
198  "is not callable.");
199  }
200 
201  auto new_callback =
202  [callback, this](size_t number_of_requests) {
203  try {
204  callback(number_of_requests);
205  } catch (const std::exception & exception) {
206  RCLCPP_ERROR_STREAM(
207  node_logger_,
208  "rclcpp::ServiceBase@" << this <<
209  " caught " << rmw::impl::cpp::demangle(exception) <<
210  " exception in user-provided callback for the 'on new request' callback: " <<
211  exception.what());
212  } catch (...) {
213  RCLCPP_ERROR_STREAM(
214  node_logger_,
215  "rclcpp::ServiceBase@" << this <<
216  " caught unhandled exception in user-provided callback " <<
217  "for the 'on new request' callback");
218  }
219  };
220 
221  std::lock_guard<std::recursive_mutex> lock(callback_mutex_);
222 
223  // Set it temporarily to the new callback, while we replace the old one.
224  // This two-step setting, prevents a gap where the old std::function has
225  // been replaced but the middleware hasn't been told about the new one yet.
227  rclcpp::detail::cpp_callback_trampoline<decltype(new_callback), const void *, size_t>,
228  static_cast<const void *>(&new_callback));
229 
230  // Store the std::function to keep it in scope, also overwrites the existing one.
231  on_new_request_callback_ = new_callback;
232 
233  // Set it again, now using the permanent storage.
235  rclcpp::detail::cpp_callback_trampoline<
236  decltype(on_new_request_callback_), const void *, size_t>,
237  static_cast<const void *>(&on_new_request_callback_));
238  }
239 
241  void
243  {
244  std::lock_guard<std::recursive_mutex> lock(callback_mutex_);
245  if (on_new_request_callback_) {
246  set_on_new_request_callback(nullptr, nullptr);
247  on_new_request_callback_ = nullptr;
248  }
249  }
250 
251 protected:
252  RCLCPP_DISABLE_COPY(ServiceBase)
253 
254  RCLCPP_PUBLIC
255  rcl_node_t *
256  get_rcl_node_handle();
257 
258  RCLCPP_PUBLIC
259  const rcl_node_t *
260  get_rcl_node_handle() const;
261 
262  RCLCPP_PUBLIC
263  void
264  set_on_new_request_callback(rcl_event_callback_t callback, const void * user_data);
265 
266  std::shared_ptr<rcl_node_t> node_handle_;
267 
268  std::recursive_mutex callback_mutex_;
269  // It is important to declare on_new_request_callback_ before
270  // service_handle_, so on destruction the service is
271  // destroyed first. Otherwise, the rmw service callback
272  // would point briefly to a destroyed function.
273  std::function<void(size_t)> on_new_request_callback_{nullptr};
274  // Declare service_handle_ after callback
275  std::shared_ptr<rcl_service_t> service_handle_;
276  bool owns_rcl_handle_ = true;
277 
278  rclcpp::Logger node_logger_;
279 
280  std::atomic<bool> in_use_by_wait_set_{false};
281 };
282 
283 template<typename ServiceT>
284 class Service
285  : public ServiceBase,
286  public std::enable_shared_from_this<Service<ServiceT>>
287 {
288 public:
289  using CallbackType = std::function<
290  void (
291  const std::shared_ptr<typename ServiceT::Request>,
292  std::shared_ptr<typename ServiceT::Response>)>;
293 
294  using CallbackWithHeaderType = std::function<
295  void (
296  const std::shared_ptr<rmw_request_id_t>,
297  const std::shared_ptr<typename ServiceT::Request>,
298  std::shared_ptr<typename ServiceT::Response>)>;
299  RCLCPP_SMART_PTR_DEFINITIONS(Service)
300 
301 
313  std::shared_ptr<rcl_node_t> node_handle,
314  const std::string & service_name,
315  AnyServiceCallback<ServiceT> any_callback,
316  rcl_service_options_t & service_options)
317  : ServiceBase(node_handle), any_callback_(any_callback),
318  srv_type_support_handle_(rosidl_typesupport_cpp::get_service_type_support_handle<ServiceT>())
319  {
320  // rcl does the static memory allocation here
321  service_handle_ = std::shared_ptr<rcl_service_t>(
322  new rcl_service_t, [handle = node_handle_, service_name](rcl_service_t * service)
323  {
324  if (rcl_service_fini(service, handle.get()) != RCL_RET_OK) {
325  RCLCPP_ERROR(
326  rclcpp::get_node_logger(handle.get()).get_child("rclcpp"),
327  "Error in destruction of rcl service handle: %s",
328  rcl_get_error_string().str);
329  rcl_reset_error();
330  }
331  delete service;
332  });
333  *service_handle_.get() = rcl_get_zero_initialized_service();
334 
336  service_handle_.get(),
337  node_handle.get(),
338  srv_type_support_handle_,
339  service_name.c_str(),
340  &service_options);
341  if (ret != RCL_RET_OK) {
342  if (ret == RCL_RET_SERVICE_NAME_INVALID) {
343  auto rcl_node_handle = get_rcl_node_handle();
344  // this will throw on any validation problem
345  rcl_reset_error();
347  service_name,
348  rcl_node_get_name(rcl_node_handle),
349  rcl_node_get_namespace(rcl_node_handle),
350  true);
351  }
352 
353  rclcpp::exceptions::throw_from_rcl_error(ret, "could not create service");
354  }
355  TRACETOOLS_TRACEPOINT(
356  rclcpp_service_callback_added,
357  static_cast<const void *>(get_service_handle().get()),
358  static_cast<const void *>(&any_callback_));
359 #ifndef TRACETOOLS_DISABLED
360  any_callback_.register_callback_for_tracing();
361 #endif
362  }
363 
365 
375  std::shared_ptr<rcl_node_t> node_handle,
376  std::shared_ptr<rcl_service_t> service_handle,
377  AnyServiceCallback<ServiceT> any_callback)
378  : ServiceBase(node_handle), any_callback_(any_callback),
379  srv_type_support_handle_(rosidl_typesupport_cpp::get_service_type_support_handle<ServiceT>())
380  {
381  // check if service handle was initialized
382  if (!rcl_service_is_valid(service_handle.get())) {
383  // *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
384  throw std::runtime_error(
385  std::string("rcl_service_t in constructor argument must be initialized beforehand."));
386  // *INDENT-ON*
387  }
388 
389  service_handle_ = service_handle;
390  TRACETOOLS_TRACEPOINT(
391  rclcpp_service_callback_added,
392  static_cast<const void *>(get_service_handle().get()),
393  static_cast<const void *>(&any_callback_));
394 #ifndef TRACETOOLS_DISABLED
395  any_callback_.register_callback_for_tracing();
396 #endif
397  }
398 
400 
410  std::shared_ptr<rcl_node_t> node_handle,
411  rcl_service_t * service_handle,
412  AnyServiceCallback<ServiceT> any_callback)
413  : ServiceBase(node_handle), any_callback_(any_callback),
414  srv_type_support_handle_(rosidl_typesupport_cpp::get_service_type_support_handle<ServiceT>())
415  {
416  // check if service handle was initialized
417  if (!rcl_service_is_valid(service_handle)) {
418  // *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
419  throw std::runtime_error(
420  std::string("rcl_service_t in constructor argument must be initialized beforehand."));
421  // *INDENT-ON*
422  }
423 
424  // In this case, rcl owns the service handle memory
425  service_handle_ = std::shared_ptr<rcl_service_t>(new rcl_service_t);
426  service_handle_->impl = service_handle->impl;
427  TRACETOOLS_TRACEPOINT(
428  rclcpp_service_callback_added,
429  static_cast<const void *>(get_service_handle().get()),
430  static_cast<const void *>(&any_callback_));
431 #ifndef TRACETOOLS_DISABLED
432  any_callback_.register_callback_for_tracing();
433 #endif
434  }
435 
436  Service() = delete;
437 
438  virtual ~Service()
439  {
440  }
441 
443 
454  bool
455  take_request(typename ServiceT::Request & request_out, rmw_request_id_t & request_id_out)
456  {
457  return this->take_type_erased_request(&request_out, request_id_out);
458  }
459 
460  std::shared_ptr<void>
461  create_request() override
462  {
463  return std::make_shared<typename ServiceT::Request>();
464  }
465 
466  std::shared_ptr<rmw_request_id_t>
467  create_request_header() override
468  {
469  return std::make_shared<rmw_request_id_t>();
470  }
471 
472  void
473  handle_request(
474  std::shared_ptr<rmw_request_id_t> request_header,
475  std::shared_ptr<void> request) override
476  {
477  auto typed_request = std::static_pointer_cast<typename ServiceT::Request>(request);
478  auto response = any_callback_.dispatch(this->shared_from_this(), request_header, typed_request);
479  if (response) {
480  send_response(*request_header, *response);
481  }
482  }
483 
484  void
485  send_response(rmw_request_id_t & req_id, typename ServiceT::Response & response)
486  {
487  rcl_ret_t ret = rcl_send_response(get_service_handle().get(), &req_id, &response);
488 
489  if (ret == RCL_RET_TIMEOUT) {
490  RCLCPP_WARN(
491  node_logger_.get_child("rclcpp"),
492  "failed to send response to %s (timeout): %s",
493  this->get_service_name(), rcl_get_error_string().str);
494  rcl_reset_error();
495  return;
496  }
497  if (ret != RCL_RET_OK) {
498  rclcpp::exceptions::throw_from_rcl_error(ret, "failed to send response");
499  }
500  }
501 
503 
511  void
513  Clock::SharedPtr clock, const QoS & qos_service_event_pub,
514  rcl_service_introspection_state_t introspection_state)
515  {
517  pub_opts.qos = qos_service_event_pub.get_rmw_qos_profile();
518 
520  service_handle_.get(),
521  node_handle_.get(),
522  clock->get_clock_handle(),
523  srv_type_support_handle_,
524  pub_opts,
525  introspection_state);
526 
527  if (RCL_RET_OK != ret) {
528  rclcpp::exceptions::throw_from_rcl_error(ret, "failed to configure service introspection");
529  }
530  }
531 
532 private:
533  RCLCPP_DISABLE_COPY(Service)
534 
535  AnyServiceCallback<ServiceT> any_callback_;
536 
537  const rosidl_service_type_support_t * srv_type_support_handle_;
538 };
539 
540 } // namespace rclcpp
541 
542 #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.cpp:73
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
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:83
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:108
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:89
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:193
void clear_on_new_request_callback()
Unset the callback registered for new requests, if any.
Definition: service.hpp:242
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:59
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:38
RCLCPP_PUBLIC const char * get_service_name()
Return the name of the service.
Definition: service.cpp:53
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:455
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:374
Service(std::shared_ptr< rcl_node_t > node_handle, rcl_service_t *service_handle, AnyServiceCallback< ServiceT > any_callback)
Default constructor.
Definition: service.hpp:409
void configure_introspection(Clock::SharedPtr clock, const QoS &qos_service_event_pub, rcl_service_introspection_state_t introspection_state)
Configure service introspection.
Definition: service.hpp:512
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:408
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:417
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:220
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:86
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_service_configure_service_introspection(rcl_service_t *service, 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)
Configure service introspection features for the service.
Definition: service.c:471
RCL_PUBLIC bool rcl_service_is_valid(const rcl_service_t *service)
Check that the service is valid.
Definition: service.c:425
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:234
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:55
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:384
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
Options available for a rcl service.
Definition: service.h:50
Structure which encapsulates a ROS Service.
Definition: service.h:43
rcl_service_impl_t * impl
Pointer to the service implementation.
Definition: service.h:45
#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
#define RCL_RET_TIMEOUT
Timeout occurred return code.
Definition: types.h:31
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.
Definition: types.h:24