15 #ifndef RCLCPP__SERVICE_HPP_
16 #define RCLCPP__SERVICE_HPP_
26 #include "rcl/error_handling.h"
27 #include "rcl/event_callback.h"
29 #include "rcl/service_introspection.h"
31 #include "rmw/error_handling.h"
32 #include "rmw/impl/cpp/demangle.hpp"
35 #include "tracetools/tracetools.h"
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"
54 RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(
ServiceBase)
57 explicit ServiceBase(std::shared_ptr<rcl_node_t> node_handle);
74 std::shared_ptr<rcl_service_t>
83 std::shared_ptr<const rcl_service_t>
106 std::shared_ptr<void>
107 create_request() = 0;
110 std::shared_ptr<rmw_request_id_t>
111 create_request_header() = 0;
116 std::shared_ptr<rmw_request_id_t> request_header,
117 std::shared_ptr<void> request) = 0;
196 throw std::invalid_argument(
197 "The callback passed to set_on_new_request_callback "
202 [callback,
this](
size_t number_of_requests) {
204 callback(number_of_requests);
205 }
catch (
const std::exception & exception) {
208 "rclcpp::ServiceBase@" <<
this <<
209 " caught " << rmw::impl::cpp::demangle(exception) <<
210 " exception in user-provided callback for the 'on new request' callback: " <<
215 "rclcpp::ServiceBase@" <<
this <<
216 " caught unhandled exception in user-provided callback " <<
217 "for the 'on new request' callback");
221 std::lock_guard<std::recursive_mutex> lock(callback_mutex_);
227 rclcpp::detail::cpp_callback_trampoline<decltype(new_callback),
const void *,
size_t>,
228 static_cast<const void *
>(&new_callback));
231 on_new_request_callback_ = new_callback;
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_));
244 std::lock_guard<std::recursive_mutex> lock(callback_mutex_);
245 if (on_new_request_callback_) {
247 on_new_request_callback_ =
nullptr;
256 get_rcl_node_handle();
260 get_rcl_node_handle()
const;
266 std::shared_ptr<rcl_node_t> node_handle_;
268 std::recursive_mutex callback_mutex_;
273 std::function<void(
size_t)> on_new_request_callback_{
nullptr};
275 std::shared_ptr<rcl_service_t> service_handle_;
276 bool owns_rcl_handle_ =
true;
280 std::atomic<bool> in_use_by_wait_set_{
false};
283 template<
typename ServiceT>
286 public std::enable_shared_from_this<Service<ServiceT>>
289 using CallbackType = std::function<
291 const std::shared_ptr<typename ServiceT::Request>,
292 std::shared_ptr<typename ServiceT::Response>)>;
294 using CallbackWithHeaderType = std::function<
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)
314 const std::
string & service_name,
317 :
ServiceBase(node_handle), any_callback_(any_callback),
318 srv_type_support_handle_(rosidl_typesupport_cpp::get_service_type_support_handle<ServiceT>())
321 service_handle_ = std::shared_ptr<rcl_service_t>(
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);
336 service_handle_.get(),
338 srv_type_support_handle_,
339 service_name.c_str(),
343 auto rcl_node_handle = get_rcl_node_handle();
353 rclcpp::exceptions::throw_from_rcl_error(ret,
"could not create service");
355 TRACETOOLS_TRACEPOINT(
356 rclcpp_service_callback_added,
358 static_cast<const void *
>(&any_callback_));
359 #ifndef TRACETOOLS_DISABLED
360 any_callback_.register_callback_for_tracing();
375 std::shared_ptr<rcl_node_t> node_handle,
376 std::shared_ptr<rcl_service_t> service_handle,
378 :
ServiceBase(node_handle), any_callback_(any_callback),
379 srv_type_support_handle_(rosidl_typesupport_cpp::get_service_type_support_handle<ServiceT>())
384 throw std::runtime_error(
385 std::string(
"rcl_service_t in constructor argument must be initialized beforehand."));
389 service_handle_ = service_handle;
390 TRACETOOLS_TRACEPOINT(
391 rclcpp_service_callback_added,
393 static_cast<const void *
>(&any_callback_));
394 #ifndef TRACETOOLS_DISABLED
395 any_callback_.register_callback_for_tracing();
410 std::shared_ptr<rcl_node_t> node_handle,
413 :
ServiceBase(node_handle), any_callback_(any_callback),
414 srv_type_support_handle_(rosidl_typesupport_cpp::get_service_type_support_handle<ServiceT>())
419 throw std::runtime_error(
420 std::string(
"rcl_service_t in constructor argument must be initialized beforehand."));
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,
430 static_cast<const void *
>(&any_callback_));
431 #ifndef TRACETOOLS_DISABLED
432 any_callback_.register_callback_for_tracing();
455 take_request(
typename ServiceT::Request & request_out, rmw_request_id_t & request_id_out)
460 std::shared_ptr<void>
461 create_request()
override
463 return std::make_shared<typename ServiceT::Request>();
466 std::shared_ptr<rmw_request_id_t>
467 create_request_header()
override
469 return std::make_shared<rmw_request_id_t>();
474 std::shared_ptr<rmw_request_id_t> request_header,
475 std::shared_ptr<void> request)
override
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);
480 send_response(*request_header, *response);
485 send_response(rmw_request_id_t & req_id,
typename ServiceT::Response & response)
492 "failed to send response to %s (timeout): %s",
493 this->get_service_name(), rcl_get_error_string().str);
498 rclcpp::exceptions::throw_from_rcl_error(ret,
"failed to send response");
513 Clock::SharedPtr clock,
const QoS & qos_service_event_pub,
514 rcl_service_introspection_state_t introspection_state)
520 service_handle_.get(),
522 clock->get_clock_handle(),
523 srv_type_support_handle_,
525 introspection_state);
528 rclcpp::exceptions::throw_from_rcl_error(ret,
"failed to configure service introspection");
537 const rosidl_service_type_support_t * srv_type_support_handle_;
RCLCPP_PUBLIC Logger get_child(const std::string &suffix)
Return a logger that is a descendant of this logger.
Encapsulation of Quality of Service settings.
rmw_qos_profile_t & get_rmw_qos_profile()
Return the rmw qos profile.
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.
RCLCPP_PUBLIC rclcpp::QoS get_request_subscription_actual_qos() const
Get the actual request subscription QoS settings, after the defaults have been determined.
RCLCPP_PUBLIC rclcpp::QoS get_response_publisher_actual_qos() const
Get the actual response publisher QoS settings, after the defaults have been determined.
void set_on_new_request_callback(std::function< void(size_t)> callback)
Set a callback to be called when each new request is received.
void clear_on_new_request_callback()
Unset the callback registered for new requests, if any.
RCLCPP_PUBLIC std::shared_ptr< rcl_service_t > get_service_handle()
Return the rcl_service_t service handle in a std::shared_ptr.
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.
RCLCPP_PUBLIC const char * get_service_name()
Return the name of the service.
bool take_request(typename ServiceT::Request &request_out, rmw_request_id_t &request_id_out)
Take the next request from the service.
Service(std::shared_ptr< rcl_node_t > node_handle, std::shared_ptr< rcl_service_t > service_handle, AnyServiceCallback< ServiceT > any_callback)
Default constructor.
Service(std::shared_ptr< rcl_node_t > node_handle, rcl_service_t *service_handle, AnyServiceCallback< ServiceT > any_callback)
Default constructor.
void configure_introspection(Clock::SharedPtr clock, const QoS &qos_service_event_pub, rcl_service_introspection_state_t introspection_state)
Configure service introspection.
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.
RCL_PUBLIC RCL_WARN_UNUSED const char * rcl_node_get_namespace(const rcl_node_t *node)
Return the namespace of the node.
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.
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.
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.
RCL_PUBLIC bool rcl_service_is_valid(const rcl_service_t *service)
Check that the service is valid.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_service_fini(rcl_service_t *service, rcl_node_t *node)
Finalize a rcl_service_t.
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.
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.
Structure which encapsulates a ROS Node.
Options available for a rcl publisher.
rmw_qos_profile_t qos
Middleware quality of service settings for the publisher.
Options available for a rcl service.
Structure which encapsulates a ROS Service.
rcl_service_impl_t * impl
Pointer to the service implementation.
#define RCL_RET_SERVICE_NAME_INVALID
Service name (same as topic name) does not pass validation.
#define RCL_RET_OK
Success return code.
#define RCL_RET_TIMEOUT
Timeout occurred return code.
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.