Class ClientBase
Defined in File client_base.hpp
Inheritance Relationships
Base Type
public rclcpp::Waitable
Derived Types
public rclcpp_action::Client< ActionT >
(Template Class Client)public rclcpp_action::GenericClient
(Class GenericClient)
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
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 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
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
-
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 std::shared_ptr<void> create_goal_response() const = 0
-
virtual std::shared_ptr<void> create_result_response() const = 0
-
virtual std::shared_ptr<void> create_cancel_response() const = 0
-
virtual std::shared_ptr<void> create_feedback_message() const = 0
-
virtual std::shared_ptr<void> create_status_message() const = 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_
-
virtual ~ClientBase()