Class ClientBase

Inheritance Relationships

Base Type

  • public rclcpp::Waitable

Derived Types

Class Documentation

class ClientBase : public rclcpp::Waitable

Base Action Client implementation This class should not be used directly by users wanting to create an aciton client. Instead users should use rclcpp_action::Client<>.

Internally, this class is responsible for interfacing with the rcl_action API.

Subclassed by rclcpp_action::Client< ActionT >, rclcpp_action::GenericClient

Public Types

enum class EntityType : std::size_t

Enum to identify entities belonging to the action client.

Values:

enumerator GoalClient
enumerator ResultClient
enumerator CancelClient
enumerator FeedbackSubscription
enumerator StatusSubscription

Public Functions

virtual ~ClientBase()
bool action_server_is_ready() const

Return true if there is an action server that is ready to take goal requests.

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

Wait for action_server_is_ready() to become true, or until the given timeout is reached.

size_t get_number_of_ready_subscriptions() override
size_t get_number_of_ready_timers() override
size_t get_number_of_ready_clients() override
size_t get_number_of_ready_services() override
size_t get_number_of_ready_guard_conditions() override
void add_to_wait_set(rcl_wait_set_t &wait_set) override
bool is_ready(const rcl_wait_set_t &wait_set) override
std::shared_ptr<void> take_data() override
std::shared_ptr<void> take_data_by_entity_id(size_t id) override
void execute(const std::shared_ptr<void> &data) override
void set_on_ready_callback(std::function<void(size_t, int)> callback) override

The callback receives a size_t which is the number of messages received since the last time this callback was called. Normally this is 1, but can be > 1 if messages were received before any callback was set.

The callback also receives an int identifier argument, which identifies the action client entity which is ready. This implies that the provided callback can use the identifier to behave differently depending on which entity triggered the waitable to become ready.

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 subscription or other information, you may use a lambda with captures or std::bind.

Parameters:

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

void clear_on_ready_callback() override

Unset the callback registered for new events, if any.

std::vector<std::shared_ptr<rclcpp::TimerBase>> get_timers() const override
void configure_introspection(rclcpp::Clock::SharedPtr clock, const rclcpp::QoS &qos_service_event_pub, rcl_service_introspection_state_t introspection_state)

Configure action 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

Throws:
  • std::invalid_argument – if clock is nullptr

  • rclcpp::exceptions::throw_from_rcl_error – if rcl error occurs.

Protected Types

using ResponseCallback = std::function<void(std::shared_ptr<void> response)>

Protected Functions

ClientBase(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, const std::string &action_name, const rosidl_action_type_support_t *type_support, const rcl_action_client_options_t &options)
bool wait_for_action_server_nanoseconds(std::chrono::nanoseconds timeout)

Wait for action_server_is_ready() to become true, or until the given timeout is reached.

rclcpp::Logger get_logger()
virtual GoalUUID generate_goal_id()
virtual void send_goal_request(std::shared_ptr<void> request, ResponseCallback callback)
virtual void send_result_request(std::shared_ptr<void> request, ResponseCallback callback)
virtual void send_cancel_request(std::shared_ptr<void> request, ResponseCallback callback)
virtual std::shared_ptr<void> create_goal_response() const = 0
virtual void handle_goal_response(const rmw_request_id_t &response_header, std::shared_ptr<void> goal_response)
virtual std::shared_ptr<void> create_result_response() const = 0
virtual void handle_result_response(const rmw_request_id_t &response_header, std::shared_ptr<void> result_response)
virtual std::shared_ptr<void> create_cancel_response() const = 0
virtual void handle_cancel_response(const rmw_request_id_t &response_header, std::shared_ptr<void> cancel_response)
virtual std::shared_ptr<void> create_feedback_message() const = 0
virtual void handle_feedback_message(std::shared_ptr<void> message) = 0
virtual std::shared_ptr<void> create_status_message() const = 0
virtual void handle_status_message(std::shared_ptr<void> message) = 0
void set_on_ready_callback(EntityType entity_type, rcl_event_callback_t callback, const void *user_data)

Protected Attributes

std::recursive_mutex listener_mutex_
std::unordered_map<EntityType, std::function<void(size_t)>> entity_type_to_on_ready_callback_