ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
Public Types | Public Member Functions | List of all members
rclcpp::Service< ServiceT > Class Template Reference
Inheritance diagram for rclcpp::Service< ServiceT >:
Inheritance graph
[legend]
Collaboration diagram for rclcpp::Service< ServiceT >:
Collaboration graph
[legend]

Public Types

using CallbackType = std::function< void(const std::shared_ptr< typename ServiceT::Request >, std::shared_ptr< typename ServiceT::Response >)>
 
using CallbackWithHeaderType = std::function< void(const std::shared_ptr< rmw_request_id_t >, const std::shared_ptr< typename ServiceT::Request >, std::shared_ptr< typename ServiceT::Response >)>
 

Public Member Functions

 Service (std::shared_ptr< rcl_node_t > node_handle, const std::string &service_name, AnyServiceCallback< ServiceT > any_callback, rcl_service_options_t &service_options)
 Default constructor. More...
 
 Service (std::shared_ptr< rcl_node_t > node_handle, std::shared_ptr< rcl_service_t > service_handle, AnyServiceCallback< ServiceT > any_callback)
 Default constructor. More...
 
 Service (std::shared_ptr< rcl_node_t > node_handle, rcl_service_t *service_handle, AnyServiceCallback< ServiceT > any_callback)
 Default constructor. More...
 
bool take_request (typename ServiceT::Request &request_out, rmw_request_id_t &request_id_out)
 Take the next request from the service. More...
 
std::shared_ptr< void > create_request () override
 
std::shared_ptr< rmw_request_id_t > create_request_header () override
 
void handle_request (std::shared_ptr< rmw_request_id_t > request_header, std::shared_ptr< void > request) override
 
void send_response (rmw_request_id_t &req_id, typename ServiceT::Response &response)
 
- Public Member Functions inherited from rclcpp::ServiceBase
RCLCPP_PUBLIC ServiceBase (std::shared_ptr< rcl_node_t > node_handle)
 
RCLCPP_PUBLIC const char * get_service_name ()
 Return the name of the service. More...
 
RCLCPP_PUBLIC std::shared_ptr< rcl_service_tget_service_handle ()
 Return the rcl_service_t service handle in a std::shared_ptr. More...
 
RCLCPP_PUBLIC std::shared_ptr< const rcl_service_tget_service_handle () const
 Return the rcl_service_t service handle in a std::shared_ptr. More...
 
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. More...
 
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. More...
 
RCLCPP_PUBLIC rclcpp::QoS get_response_publisher_actual_qos () const
 Get the actual response publisher QoS settings, after the defaults have been determined. More...
 
RCLCPP_PUBLIC rclcpp::QoS get_request_subscription_actual_qos () const
 Get the actual request subscription QoS settings, after the defaults have been determined. More...
 
void set_on_new_request_callback (std::function< void(size_t)> callback)
 Set a callback to be called when each new request is received. More...
 
void clear_on_new_request_callback ()
 Unset the callback registered for new requests, if any.
 

Additional Inherited Members

- Protected Member Functions inherited from rclcpp::ServiceBase
RCLCPP_PUBLIC rcl_node_tget_rcl_node_handle ()
 
RCLCPP_PUBLIC const rcl_node_tget_rcl_node_handle () const
 
RCLCPP_PUBLIC void set_on_new_request_callback (rcl_event_callback_t callback, const void *user_data)
 
- Protected Attributes inherited from rclcpp::ServiceBase
std::shared_ptr< rcl_node_tnode_handle_
 
std::shared_ptr< rcl_service_tservice_handle_
 
bool owns_rcl_handle_ = true
 
rclcpp::Logger node_logger_
 
std::atomic< bool > in_use_by_wait_set_ {false}
 
std::recursive_mutex callback_mutex_
 
std::function< void(size_t)> on_new_request_callback_ {nullptr}
 

Detailed Description

template<typename ServiceT>
class rclcpp::Service< ServiceT >

Definition at line 277 of file service.hpp.

Constructor & Destructor Documentation

◆ Service() [1/3]

template<typename ServiceT >
rclcpp::Service< ServiceT >::Service ( std::shared_ptr< rcl_node_t node_handle,
const std::string &  service_name,
AnyServiceCallback< ServiceT >  any_callback,
rcl_service_options_t service_options 
)
inline

Default constructor.

The constructor for a Service is almost never called directly. Instead, services should be instantiated through the function rclcpp::create_service().

Parameters
[in]node_handleNodeBaseInterface pointer that is used in part of the setup.
[in]service_nameName of the topic to publish to.
[in]any_callbackUser defined callback to call when a client request is received.
[in]service_optionsoptions for the subscription.

Definition at line 305 of file service.hpp.

References rclcpp::expand_topic_or_service_name(), rclcpp::ServiceBase::get_service_handle(), rcl_get_zero_initialized_service(), rcl_node_get_name(), rcl_node_get_namespace(), RCL_RET_OK, RCL_RET_SERVICE_NAME_INVALID, rcl_service_fini(), and rcl_service_init().

Here is the call graph for this function:

◆ Service() [2/3]

template<typename ServiceT >
rclcpp::Service< ServiceT >::Service ( std::shared_ptr< rcl_node_t node_handle,
std::shared_ptr< rcl_service_t service_handle,
AnyServiceCallback< ServiceT >  any_callback 
)
inline

Default constructor.

The constructor for a Service is almost never called directly. Instead, services should be instantiated through the function rclcpp::create_service().

Parameters
[in]node_handleNodeBaseInterface pointer that is used in part of the setup.
[in]service_handleservice handle.
[in]any_callbackUser defined callback to call when a client request is received.

Definition at line 369 of file service.hpp.

References rclcpp::ServiceBase::get_service_handle(), and rcl_service_is_valid().

Here is the call graph for this function:

◆ Service() [3/3]

template<typename ServiceT >
rclcpp::Service< ServiceT >::Service ( std::shared_ptr< rcl_node_t node_handle,
rcl_service_t service_handle,
AnyServiceCallback< ServiceT >  any_callback 
)
inline

Default constructor.

The constructor for a Service is almost never called directly. Instead, services should be instantiated through the function rclcpp::create_service().

Parameters
[in]node_handleNodeBaseInterface pointer that is used in part of the setup.
[in]service_handleservice handle.
[in]any_callbackUser defined callback to call when a client request is received.

Definition at line 404 of file service.hpp.

References rclcpp::ServiceBase::get_service_handle(), rcl_service_s::impl, and rcl_service_is_valid().

Here is the call graph for this function:

Member Function Documentation

◆ take_request()

template<typename ServiceT >
bool rclcpp::Service< ServiceT >::take_request ( typename ServiceT::Request &  request_out,
rmw_request_id_t &  request_id_out 
)
inline

Take the next request from the service.

See also
ServiceBase::take_type_erased_request().
Parameters
[out]request_outThe reference to a service request object into which the middleware will copy the taken request.
[out]request_id_outThe output id for the request which can be used to associate response with this request in the future.
Returns
true if the request was taken, otherwise false.
Exceptions
rclcpp::exceptions::RCLErrorbased exceptions if the underlying rcl calls fail.

Definition at line 450 of file service.hpp.

References rclcpp::ServiceBase::take_type_erased_request().

Here is the call graph for this function:

The documentation for this class was generated from the following files: