Class ClientBase

Inheritance Relationships

Derived Types

Class Documentation

class ClientBase

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

Public Functions

ClientBase(rclcpp::node_interfaces::NodeBaseInterface *node_base, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph)
virtual ~ClientBase() = default
bool take_type_erased_response(void *response_out, rmw_request_id_t &request_header_out)

Take the next response for this client as a type erased pointer.

The type erased pointer allows for this method to be used in a type agnostic way along with ClientBase::create_response(), ClientBase::create_request_header(), and ClientBase::handle_response(). The typed version of this can be used if the Service type is known,

Parameters:
  • response_out[out] The type erased pointer 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.

const char *get_service_name() const

Return the name of the service.

Returns:

The name of the service.

std::shared_ptr<rcl_client_t> get_client_handle()

Return the rcl_client_t client handle in a std::shared_ptr.

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

std::shared_ptr<const rcl_client_t> get_client_handle() const

Return the rcl_client_t client handle in a std::shared_ptr.

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

bool service_is_ready() const

Return if the service is ready.

Returns:

true if the service is ready, false otherwise

template<typename RepT = int64_t, typename RatioT = std::milli>
inline bool wait_for_service(std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))

Wait for a service to be ready.

Parameters:

timeout – maximum time to wait

Returns:

true if the service is ready and the timeout is not over, false otherwise

virtual std::shared_ptr<void> create_response() = 0
virtual std::shared_ptr<rmw_request_id_t> create_request_header() = 0
virtual void handle_response(std::shared_ptr<rmw_request_id_t> request_header, std::shared_ptr<void> response) = 0
bool exchange_in_use_by_wait_set_state(bool in_use_state)

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

This is used to ensure this client 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_request_publisher_actual_qos() const

Get the actual request publsher 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 client, 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 publsher qos settings.

rclcpp::QoS get_response_subscription_actual_qos() const

Get the actual response 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 client, 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 subscription qos settings.

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

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

The callback receives a size_t which is the number of responses received since the last time this callback was called. Normally this is 1, but can be > 1 if responses 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 client or other information, you may use a lambda with captures or std::bind.

See also

rmw_client_set_on_new_response_callback

See also

rcl_client_set_on_new_response_callback

Parameters:

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

inline void clear_on_new_response_callback()

Unset the callback registered for new responses, if any.

Protected Functions

bool wait_for_service_nanoseconds(std::chrono::nanoseconds timeout)
rcl_node_t *get_rcl_node_handle()
const rcl_node_t *get_rcl_node_handle() const
void set_on_new_response_callback(rcl_event_callback_t callback, const void *user_data)

Protected Attributes

rclcpp::node_interfaces::NodeGraphInterface::WeakPtr node_graph_
std::shared_ptr<rcl_node_t> node_handle_
std::shared_ptr<rclcpp::Context> context_
rclcpp::Logger node_logger_
std::shared_ptr<rcl_client_t> client_handle_
std::atomic<bool> in_use_by_wait_set_ = {false}
std::recursive_mutex callback_mutex_
std::function<void(size_t)> on_new_response_callback_ = {nullptr}