Template Class ServiceClient

Class Documentation

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

A simple wrapper on ROS2 services client.

Public Types

using RequestType = typename ServiceT::Request
using ResponseType = typename ServiceT::Response
using SharedPtr = std::shared_ptr<ServiceClient<ServiceT, NodeT>>

Public Functions

inline explicit ServiceClient(const std::string &service_name, const NodeT &provided_node, bool use_internal_executor = false)

A constructor.

Parameters:
  • service_name – name of the service to call

  • provided_node – Node to create the service client off of

  • use_internal_executor – Whether to create an internal executor or not

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 std::shared_future<typename ResponseType::SharedPtr> async_call(typename RequestType::SharedPtr &request)

Asynchronously call the service.

Parameters:

request – The request object to call the service using

Returns:

std::shared_future<typename ResponseType::SharedPtr> The shared future of the service response

template<typename CallbackT>
inline void async_call(typename RequestType::SharedPtr request, CallbackT &&callback)

Asynchronously call the service with a callback.

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

  • callback – The callback to call when the service response is received

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

template<typename FutureT>
inline rclcpp::FutureReturnCode spin_until_complete(const FutureT &future, const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1))

Spins the executor until the provided future is complete or the timeout is reached.

Parameters:
  • future – The shared future to wait for completion.

  • timeout – The maximum time to wait for the future to complete. Default is -1 (no timeout).

Returns:

rclcpp::FutureReturnCode indicating the result of the spin operation.

inline std::string getServiceName()

Gets the service name.

Returns:

string Service name

inline void stop()

Stop any running spin operations on the internal executor.

Protected Attributes

std::string service_name_
NodeT node_
rclcpp::CallbackGroup::SharedPtr callback_group_ = {nullptr}
rclcpp::executors::SingleThreadedExecutor::SharedPtr callback_group_executor_
rclcpp::Client<ServiceT>::SharedPtr client_
bool use_internal_executor_