Template Class Client

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

template<typename ServiceT>
class Client : public rclcpp::ClientBase

Public Types

using Request = typename ServiceT::Request
using Response = typename ServiceT::Response
using SharedRequest = typename ServiceT::Request::SharedPtr
using SharedResponse = typename ServiceT::Response::SharedPtr
using Promise = std::promise<SharedResponse>
using PromiseWithRequest = std::promise<std::pair<SharedRequest, SharedResponse>>
using SharedPromise = std::shared_ptr<Promise>
using SharedPromiseWithRequest = std::shared_ptr<PromiseWithRequest>
using Future = std::future<SharedResponse>
using SharedFuture = std::shared_future<SharedResponse>
using SharedFutureWithRequest = std::shared_future<std::pair<SharedRequest, SharedResponse>>
using CallbackType = std::function<void(SharedFuture)>
using CallbackWithRequestType = std::function<void(SharedFutureWithRequest)>

Public Functions

inline Client(rclcpp::node_interfaces::NodeBaseInterface *node_base, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph, const std::string &service_name, rcl_client_options_t &client_options)

Default constructor.

The constructor for a Client is almost never called directly. Instead, clients should be instantiated through the function rclcpp::create_client().

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

  • node_graph[in] The node graph interface of the corresponding node.

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

  • client_options[in] options for the subscription.

inline virtual ~Client()
inline bool take_response(typename ServiceT::Response &response_out, rmw_request_id_t &request_header_out)

Take the next response for this client.

Parameters:
  • response_out[out] The reference to a Service Response into which the middleware will copy the response being taken.

  • request_header_out[out] The request header to be filled by the middleware when taking, and which can be used to associte the response to a specific request.

Throws:

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

Returns:

true if the response was taken, otherwise false.

inline virtual std::shared_ptr<void> create_response() override

Create a shared pointer with the response type.

Returns:

shared pointer with the response type

inline virtual std::shared_ptr<rmw_request_id_t> create_request_header() override

Create a shared pointer with a rmw_request_id_t.

Returns:

shared pointer with a rmw_request_id_t

inline virtual void handle_response(std::shared_ptr<rmw_request_id_t> request_header, std::shared_ptr<void> response) override

Handle a server response.

Parameters:
  • request_header[in] used to check if the secuence number is valid

  • response[in] message with the server response

inline FutureAndRequestId async_send_request(SharedRequest request)

Send a request to the service server.

This method returns a FutureAndRequestId instance that can be passed to Executor::spin_until_future_complete() to wait until it has been completed.

If the future never completes, e.g. the call to Executor::spin_until_future_complete() times out, Client::remove_pending_request() must be called to clean the client internal state. Not doing so will make the Client instance to use more memory each time a response is not received from the service server.

auto future = client->async_send_request(my_request);
if (
  rclcpp::FutureReturnCode::TIMEOUT ==
  executor->spin_until_future_complete(future, timeout))
{
  client->remove_pending_request(future);
  // handle timeout
} else {
  handle_response(future.get());
}
Parameters:

request[in] request to be send.

Returns:

a FutureAndRequestId instance.

template<typename CallbackT, typename std::enable_if<rclcpp::function_traits::same_arguments<CallbackT, CallbackType>::value>::type* = nullptr>
inline SharedFutureAndRequestId async_send_request(SharedRequest request, CallbackT &&cb)

Send a request to the service server and schedule a callback in the executor.

Similar to the previous overload, but a callback will automatically be called when a response is received.

If the callback is never called, because we never got a reply for the service server, remove_pending_request() has to be called with the returned request id or prune_pending_requests(). Not doing so will make the Client instance use more memory each time a response is not received from the service server. In this case, it’s convenient to setup a timer to cleanup the pending requests. See for example the examples_rclcpp_async_client package in https://github.com/ros2/examples.

Parameters:
  • request[in] request to be send.

  • cb[in] callback that will be called when we get a response for this request.

Returns:

the request id representing the request just sent.

template<typename CallbackT, typename std::enable_if<rclcpp::function_traits::same_arguments<CallbackT, CallbackWithRequestType>::value>::type* = nullptr>
inline SharedFutureWithRequestAndRequestId async_send_request(SharedRequest request, CallbackT &&cb)

Send a request to the service server and schedule a callback in the executor.

Similar to the previous method, but you can get both the request and response in the callback.

Parameters:
  • request[in] request to be send.

  • cb[in] callback that will be called when we get a response for this request.

Returns:

the request id representing the request just sent.

inline bool remove_pending_request(int64_t request_id)

Cleanup a pending request.

This notifies the client that we have waited long enough for a response from the server to come, we have given up and we are not waiting for a response anymore.

Not calling this will make the client start using more memory for each request that never got a reply from the server.

Parameters:

request_id[in] request id returned by async_send_request().

Returns:

true when a pending request was removed, false if not (e.g. a response was received).

inline bool remove_pending_request(const FutureAndRequestId &future)

Cleanup a pending request.

Convenient overload, same as:

Client::remove_pending_request(this, future.request_id).

inline bool remove_pending_request(const SharedFutureAndRequestId &future)

Cleanup a pending request.

Convenient overload, same as:

Client::remove_pending_request(this, future.request_id).

inline bool remove_pending_request(const SharedFutureWithRequestAndRequestId &future)

Cleanup a pending request.

Convenient overload, same as:

Client::remove_pending_request(this, future.request_id).

inline size_t prune_pending_requests()

Clean all pending requests.

Returns:

number of pending requests that were removed.

template<typename AllocatorT = std::allocator<int64_t>>
inline size_t prune_requests_older_than(std::chrono::time_point<std::chrono::system_clock> time_point, std::vector<int64_t, AllocatorT> *pruned_requests = nullptr)

Clean all pending requests older than a time_point.

Parameters:
  • time_point[in] Requests that were sent before this point are going to be removed.

  • pruned_requests[inout] Removed requests id will be pushed to the vector if a pointer is provided.

Returns:

number of pending requests that were removed.

inline void configure_introspection(Clock::SharedPtr clock, const QoS &qos_service_event_pub, rcl_service_introspection_state_t introspection_state)

Configure client introspection.

Parameters:
  • clock[in] clock to use to generate introspection timestamps

  • qos_service_event_pub[in] QoS settings to use when creating the introspection publisher

  • introspection_state[in] the state to set introspection to

Protected Types

using CallbackTypeValueVariant = std::tuple<CallbackType, SharedFuture, Promise>
using CallbackWithRequestTypeValueVariant = std::tuple<CallbackWithRequestType, SharedRequest, SharedFutureWithRequest, PromiseWithRequest>
using CallbackInfoVariant = std::variant<std::promise<SharedResponse>, CallbackTypeValueVariant, CallbackWithRequestTypeValueVariant>

Protected Functions

inline int64_t async_send_request_impl(const Request &request, CallbackInfoVariant value)
inline std::optional<CallbackInfoVariant> get_and_erase_pending_request(int64_t request_number)

Protected Attributes

std::unordered_map<int64_t, std::pair<std::chrono::time_point<std::chrono::system_clock>, CallbackInfoVariant>> pending_requests_
std::mutex pending_requests_mutex_
struct FutureAndRequestId : public rclcpp::detail::FutureAndRequestId<std::future<SharedResponse>>

A convenient Client::Future and request id pair.

Public members:

  • future: a std::future<SharedResponse>.

  • request_id: the request id associated with the future.

All the other methods are equivalent to the ones std::future provides.

Public Functions

inline operator SharedFuture()

Deprecated, use .future.share() instead.

Allow implicit conversions to std::shared_future by value.

Deprecated:

inline SharedFuture share() noexcept

See std::future::share().

struct SharedFutureAndRequestId : public rclcpp::detail::FutureAndRequestId<std::shared_future<SharedResponse>>

A convenient Client::SharedFuture and request id pair.

Public members:

  • future: a std::shared_future<SharedResponse>.

  • request_id: the request id associated with the future.

All the other methods are equivalent to the ones std::shared_future provides.

struct SharedFutureWithRequestAndRequestId : public rclcpp::detail::FutureAndRequestId<std::shared_future<std::pair<SharedRequest, SharedResponse>>>

A convenient Client::SharedFutureWithRequest and request id pair.

Public members:

  • future: a std::shared_future<SharedResponse>.

  • request_id: the request id associated with the future.

All the other methods are equivalent to the ones std::shared_future provides.