rclcpp_action  master
C++ ROS Action Client Library
Public Member Functions | Protected Types | Protected Member Functions | List of all members
rclcpp_action::ClientBase Class Referenceabstract

#include <client.hpp>

Inheritance diagram for rclcpp_action::ClientBase:
Inheritance graph
[legend]
Collaboration diagram for rclcpp_action::ClientBase:
Collaboration graph
[legend]

Public Member Functions

virtual RCLCPP_ACTION_PUBLIC ~ClientBase ()
 
RCLCPP_ACTION_PUBLIC bool action_server_is_ready () const
 Return true if there is an action server that is ready to take goal requests. More...
 
template<typename RepT = int64_t, typename RatioT = std::milli>
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. More...
 
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_subscriptions () override
 
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_timers () override
 
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_clients () override
 
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_services () override
 
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_guard_conditions () override
 
RCLCPP_ACTION_PUBLIC bool add_to_wait_set (rcl_wait_set_t *wait_set) override
 
RCLCPP_ACTION_PUBLIC bool is_ready (rcl_wait_set_t *wait_set) override
 
RCLCPP_ACTION_PUBLIC std::shared_ptr< void > take_data () override
 
RCLCPP_ACTION_PUBLIC void execute (std::shared_ptr< void > &data) override
 
- Public Member Functions inherited from rclcpp::Waitable
virtual ~Waitable ()=default
 
virtual size_t get_number_of_ready_events ()
 
bool exchange_in_use_by_wait_set_state (bool in_use_state)
 

Protected Types

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

Protected Member Functions

RCLCPP_ACTION_PUBLIC 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)
 
RCLCPP_ACTION_PUBLIC 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. More...
 
RCLCPP_ACTION_PUBLIC rclcpp::Logger get_logger ()
 
virtual RCLCPP_ACTION_PUBLIC GoalUUID generate_goal_id ()
 
virtual RCLCPP_ACTION_PUBLIC void send_goal_request (std::shared_ptr< void > request, ResponseCallback callback)
 
virtual RCLCPP_ACTION_PUBLIC void send_result_request (std::shared_ptr< void > request, ResponseCallback callback)
 
virtual RCLCPP_ACTION_PUBLIC void send_cancel_request (std::shared_ptr< void > request, ResponseCallback callback)
 
virtual std::shared_ptr< void > create_goal_response () const =0
 
virtual RCLCPP_ACTION_PUBLIC 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 RCLCPP_ACTION_PUBLIC 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 RCLCPP_ACTION_PUBLIC 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
 

Detailed Description

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.

Member Typedef Documentation

◆ ResponseCallback

Constructor & Destructor Documentation

◆ ~ClientBase()

virtual RCLCPP_ACTION_PUBLIC rclcpp_action::ClientBase::~ClientBase ( )
virtual

◆ ClientBase()

RCLCPP_ACTION_PUBLIC rclcpp_action::ClientBase::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 
)
protected

Member Function Documentation

◆ action_server_is_ready()

RCLCPP_ACTION_PUBLIC bool rclcpp_action::ClientBase::action_server_is_ready ( ) const

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

◆ wait_for_action_server()

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

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

◆ get_number_of_ready_subscriptions()

RCLCPP_ACTION_PUBLIC size_t rclcpp_action::ClientBase::get_number_of_ready_subscriptions ( )
overridevirtual

Reimplemented from rclcpp::Waitable.

◆ get_number_of_ready_timers()

RCLCPP_ACTION_PUBLIC size_t rclcpp_action::ClientBase::get_number_of_ready_timers ( )
overridevirtual

Reimplemented from rclcpp::Waitable.

◆ get_number_of_ready_clients()

RCLCPP_ACTION_PUBLIC size_t rclcpp_action::ClientBase::get_number_of_ready_clients ( )
overridevirtual

Reimplemented from rclcpp::Waitable.

◆ get_number_of_ready_services()

RCLCPP_ACTION_PUBLIC size_t rclcpp_action::ClientBase::get_number_of_ready_services ( )
overridevirtual

Reimplemented from rclcpp::Waitable.

◆ get_number_of_ready_guard_conditions()

RCLCPP_ACTION_PUBLIC size_t rclcpp_action::ClientBase::get_number_of_ready_guard_conditions ( )
overridevirtual

Reimplemented from rclcpp::Waitable.

◆ add_to_wait_set()

RCLCPP_ACTION_PUBLIC bool rclcpp_action::ClientBase::add_to_wait_set ( rcl_wait_set_t wait_set)
overridevirtual

Implements rclcpp::Waitable.

◆ is_ready()

RCLCPP_ACTION_PUBLIC bool rclcpp_action::ClientBase::is_ready ( rcl_wait_set_t wait_set)
overridevirtual

Implements rclcpp::Waitable.

◆ take_data()

RCLCPP_ACTION_PUBLIC std::shared_ptr<void> rclcpp_action::ClientBase::take_data ( )
overridevirtual

Implements rclcpp::Waitable.

◆ execute()

RCLCPP_ACTION_PUBLIC void rclcpp_action::ClientBase::execute ( std::shared_ptr< void > &  data)
overridevirtual

Implements rclcpp::Waitable.

◆ wait_for_action_server_nanoseconds()

RCLCPP_ACTION_PUBLIC bool rclcpp_action::ClientBase::wait_for_action_server_nanoseconds ( std::chrono::nanoseconds  timeout)
protected

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

◆ get_logger()

RCLCPP_ACTION_PUBLIC rclcpp::Logger rclcpp_action::ClientBase::get_logger ( )
protected

◆ generate_goal_id()

virtual RCLCPP_ACTION_PUBLIC GoalUUID rclcpp_action::ClientBase::generate_goal_id ( )
protectedvirtual

◆ send_goal_request()

virtual RCLCPP_ACTION_PUBLIC void rclcpp_action::ClientBase::send_goal_request ( std::shared_ptr< void >  request,
ResponseCallback  callback 
)
protectedvirtual

◆ send_result_request()

virtual RCLCPP_ACTION_PUBLIC void rclcpp_action::ClientBase::send_result_request ( std::shared_ptr< void >  request,
ResponseCallback  callback 
)
protectedvirtual

◆ send_cancel_request()

virtual RCLCPP_ACTION_PUBLIC void rclcpp_action::ClientBase::send_cancel_request ( std::shared_ptr< void >  request,
ResponseCallback  callback 
)
protectedvirtual

◆ create_goal_response()

virtual std::shared_ptr<void> rclcpp_action::ClientBase::create_goal_response ( ) const
protectedpure virtual

◆ handle_goal_response()

virtual RCLCPP_ACTION_PUBLIC void rclcpp_action::ClientBase::handle_goal_response ( const rmw_request_id_t response_header,
std::shared_ptr< void >  goal_response 
)
protectedvirtual

◆ create_result_response()

virtual std::shared_ptr<void> rclcpp_action::ClientBase::create_result_response ( ) const
protectedpure virtual

◆ handle_result_response()

virtual RCLCPP_ACTION_PUBLIC void rclcpp_action::ClientBase::handle_result_response ( const rmw_request_id_t response_header,
std::shared_ptr< void >  result_response 
)
protectedvirtual

◆ create_cancel_response()

virtual std::shared_ptr<void> rclcpp_action::ClientBase::create_cancel_response ( ) const
protectedpure virtual

◆ handle_cancel_response()

virtual RCLCPP_ACTION_PUBLIC void rclcpp_action::ClientBase::handle_cancel_response ( const rmw_request_id_t response_header,
std::shared_ptr< void >  cancel_response 
)
protectedvirtual

◆ create_feedback_message()

virtual std::shared_ptr<void> rclcpp_action::ClientBase::create_feedback_message ( ) const
protectedpure virtual

◆ handle_feedback_message()

virtual void rclcpp_action::ClientBase::handle_feedback_message ( std::shared_ptr< void >  message)
protectedpure virtual

◆ create_status_message()

virtual std::shared_ptr<void> rclcpp_action::ClientBase::create_status_message ( ) const
protectedpure virtual

◆ handle_status_message()

virtual void rclcpp_action::ClientBase::handle_status_message ( std::shared_ptr< void >  message)
protectedpure virtual

The documentation for this class was generated from the following file: