Template Class ServiceClient

Class Documentation

template<class ServiceT, typename NodeT = rclcpp::Node::SharedPtr>
class ServiceClient

A simple wrapper on ROS2 services for invoke() and block-style calling.

Public Types

using RequestType = typename ServiceT::Request
using ResponseType = typename ServiceT::Response

Public Functions

inline explicit ServiceClient(const std::string &service_name, const NodeT &provided_node)

A constructor.

Parameters:
  • service_name – name of the service to call

  • provided_node – Node to create the service client off of

inline ResponseType::SharedPtr invoke(typename RequestType::SharedPtr &request, const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1))

Invoke the service and block until completed or timed out.

Parameters:
  • request – The request object to call the service using

  • timeout – Maximum timeout to wait for, default infinite

Returns:

Response A pointer to the service response from the request

inline bool invoke(typename RequestType::SharedPtr &request, typename ResponseType::SharedPtr &response)

Invoke the service and block until completed.

Parameters:
  • request – The request object to call the service using

  • Response – A pointer to the service response from the request

Returns:

bool Whether it was successfully called

inline bool wait_for_service(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds::max())

Block until a service is available or timeout.

Parameters:

timeout – Maximum timeout to wait for, default infinite

Returns:

bool true if service is available

inline std::string getServiceName()

Gets the service name.

Returns:

string Service name

Protected Attributes

std::string service_name_
NodeT node_
rclcpp::CallbackGroup::SharedPtr callback_group_
rclcpp::executors::SingleThreadedExecutor callback_group_executor_
rclcpp::Client<ServiceT>::SharedPtr client_