Template Class Service

Inheritance Relationships

Base Types

  • public rclcpp::ServiceBase (Class ServiceBase)

  • public std::enable_shared_from_this< Service< ServiceT > >

Class Documentation

template<typename ServiceT>
class Service : public rclcpp::ServiceBase, public std::enable_shared_from_this<Service<ServiceT>>

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 Functions

inline 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.

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

Parameters:
  • node_handle[in] NodeBaseInterface pointer that is used in part of the setup.

  • service_name[in] Name of the topic to publish to.

  • any_callback[in] User defined callback to call when a client request is received.

  • service_options[in] options for the subscription.

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

Default constructor.

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

Parameters:
  • node_handle[in] NodeBaseInterface pointer that is used in part of the setup.

  • service_handle[in] service handle.

  • any_callback[in] User defined callback to call when a client request is received.

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

Default constructor.

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

Parameters:
  • node_handle[in] NodeBaseInterface pointer that is used in part of the setup.

  • service_handle[in] service handle.

  • any_callback[in] User defined callback to call when a client request is received.

Service() = delete
inline virtual ~Service()
inline bool take_request(typename ServiceT::Request &request_out, rmw_request_id_t &request_id_out)

Take the next request from the service.

Parameters:
  • request_out[out] The reference 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.

inline virtual std::shared_ptr<void> create_request() override
inline virtual std::shared_ptr<rmw_request_id_t> create_request_header() override
inline virtual void handle_request(std::shared_ptr<rmw_request_id_t> request_header, std::shared_ptr<void> request) override
inline void send_response(rmw_request_id_t &req_id, typename ServiceT::Response &response)