Class ServiceBase

Inheritance Relationships

Derived Types

Class Documentation

class ServiceBase

Subclassed by rclcpp::Service< rcl_interfaces::srv::GetParameters >, rclcpp::Service< rcl_interfaces::srv::GetParameterTypes >, rclcpp::Service< rcl_interfaces::srv::SetParameters >, rclcpp::Service< rcl_interfaces::srv::SetParametersAtomically >, rclcpp::Service< rcl_interfaces::srv::DescribeParameters >, rclcpp::Service< rcl_interfaces::srv::ListParameters >, rclcpp::Service< rcl_interfaces::srv::GetLoggerLevels >, rclcpp::Service< rcl_interfaces::srv::SetLoggerLevels >, rclcpp::Service< ServiceT >

Public Functions

explicit ServiceBase(std::shared_ptr<rcl_node_t> node_handle)
virtual ~ServiceBase() = default
const char *get_service_name()

Return the name of the service.

Returns:

The name of the service.

std::shared_ptr<rcl_service_t> get_service_handle()

Return the rcl_service_t service handle in a std::shared_ptr.

This handle remains valid after the Service is destroyed. The actual rcl service is not finalized until it is out of scope everywhere.

std::shared_ptr<const rcl_service_t> get_service_handle() const

Return the rcl_service_t service handle in a std::shared_ptr.

This handle remains valid after the Service is destroyed. The actual rcl service is not finalized until it is out of scope everywhere.

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.

This type erased version of

See also

Service::take_request() is useful when using the service in a type agnostic way with methods like ServiceBase::create_request(), ServiceBase::create_request_header(), and ServiceBase::handle_request().

Parameters:
  • request_out[out] The type erased pointer to a service request object into which the middleware will copy the taken request.

  • request_id_out[out] The output id for the request which can be used to associate response with this request in the future.

Throws:

rclcpp::exceptions::RCLError – based exceptions if the underlying rcl calls fail.

Returns:

true if the request was taken, otherwise false.

virtual std::shared_ptr<void> create_request() = 0
virtual std::shared_ptr<rmw_request_id_t> create_request_header() = 0
virtual void handle_request(std::shared_ptr<rmw_request_id_t> request_header, std::shared_ptr<void> request) = 0
bool exchange_in_use_by_wait_set_state(bool in_use_state)

Exchange the “in use by wait set” state for this service.

This is used to ensure this service is not used by multiple wait sets at the same time.

Parameters:

in_use_state[in] the new state to exchange into the state, true indicates it is now in use by a wait set, and false is that it is no longer in use by a wait set.

Returns:

the previous state.

rclcpp::QoS get_response_publisher_actual_qos() const

Get the actual response publisher QoS settings, after the defaults have been determined.

The actual configuration applied when using RMW_QOS_POLICY_*_SYSTEM_DEFAULT can only be resolved after the creation of the service, and it depends on the underlying rmw implementation. If the underlying setting in use can’t be represented in ROS terms, it will be set to RMW_QOS_POLICY_*_UNKNOWN. May throw runtime_error when an unexpected error occurs.

Throws:

std::runtime_error – if failed to get qos settings

Returns:

The actual response publisher qos settings.

rclcpp::QoS get_request_subscription_actual_qos() const

Get the actual request subscription QoS settings, after the defaults have been determined.

The actual configuration applied when using RMW_QOS_POLICY_*_SYSTEM_DEFAULT can only be resolved after the creation of the service, and it depends on the underlying rmw implementation. If the underlying setting in use can’t be represented in ROS terms, it will be set to RMW_QOS_POLICY_*_UNKNOWN. May throw runtime_error when an unexpected error occurs.

Throws:

std::runtime_error – if failed to get qos settings

Returns:

The actual request subscription qos settings.

inline void set_on_new_request_callback(std::function<void(size_t)> callback)

Set a callback to be called when each new request is received.

The callback receives a size_t which is the number of requests received since the last time this callback was called. Normally this is 1, but can be > 1 if requests were received before any callback was set.

Since this callback is called from the middleware, you should aim to make it fast and not blocking. If you need to do a lot of work or wait for some other event, you should spin it off to another thread, otherwise you risk blocking the middleware.

Calling it again will clear any previously set callback.

An exception will be thrown if the callback is not callable.

This function is thread-safe.

If you want more information available in the callback, like the service or other information, you may use a lambda with captures or std::bind.

See also

rmw_service_set_on_new_request_callback

See also

rcl_service_set_on_new_request_callback

Parameters:

callback[in] functor to be called when a new request is received

inline void clear_on_new_request_callback()

Unset the callback registered for new requests, if any.

Protected Functions

rcl_node_t *get_rcl_node_handle()
const rcl_node_t *get_rcl_node_handle() const
void set_on_new_request_callback(rcl_event_callback_t callback, const void *user_data)

Protected Attributes

std::shared_ptr<rcl_node_t> node_handle_
std::recursive_mutex callback_mutex_
std::function<void(size_t)> on_new_request_callback_ = {nullptr}
std::shared_ptr<rcl_service_t> service_handle_
bool owns_rcl_handle_ = true
rclcpp::Logger node_logger_
std::atomic<bool> in_use_by_wait_set_ = {false}