rclcpp_action  master
C++ ROS Action Client Library
Public Types | Public Member Functions | List of all members
rclcpp_action::Client< ActionT > Class Template Reference

Action Client. More...

#include <client.hpp>

Inheritance diagram for rclcpp_action::Client< ActionT >:
Inheritance graph
[legend]
Collaboration diagram for rclcpp_action::Client< ActionT >:
Collaboration graph
[legend]

Public Types

using Goal = typename ActionT::Goal
 
using Feedback = typename ActionT::Feedback
 
using GoalHandle = ClientGoalHandle< ActionT >
 
using Result = typename GoalHandle::Result
 
using FeedbackCallback = typename ClientGoalHandle< ActionT >::FeedbackCallback
 
using CancelRequest = typename ActionT::CancelGoalService::Request
 
using CancelResponse = typename ActionT::CancelGoalService::Response
 

Public Member Functions

 Client (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 rcl_action_client_options_t client_options=rcl_action_client_get_default_options())
 
std::shared_future< typename GoalHandle::SharedPtr > async_send_goal (const Goal &goal, FeedbackCallback callback=nullptr, bool ignore_result=false)
 
std::shared_future< Resultasync_get_result (typename GoalHandle::SharedPtr goal_handle)
 
std::shared_future< bool > async_cancel_goal (typename GoalHandle::SharedPtr goal_handle)
 
std::shared_future< typename CancelResponse::SharedPtr > async_cancel_all_goals ()
 
std::shared_future< typename CancelResponse::SharedPtr > async_cancel_goals_before (const rclcpp::Time &stamp)
 
virtual ~Client ()
 
- Public Member Functions inherited from rclcpp_action::ClientBase
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 RatioT = std::milli>
bool wait_for_action_server (std::chrono::duration< int64_t, RatioT > timeout=std::chrono::duration< int64_t, 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 void execute () override
 

Additional Inherited Members

- Protected Types inherited from rclcpp_action::ClientBase
using ResponseCallback = std::function< void(std::shared_ptr< void > response)>
 
- Protected Member Functions inherited from rclcpp_action::ClientBase
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 GoalID 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 RCLCPP_ACTION_PUBLIC void handle_goal_response (const rmw_request_id_t &response_header, std::shared_ptr< void > goal_response)
 
virtual RCLCPP_ACTION_PUBLIC void handle_result_response (const rmw_request_id_t &response_header, std::shared_ptr< void > result_response)
 
virtual RCLCPP_ACTION_PUBLIC void handle_cancel_response (const rmw_request_id_t &response_header, std::shared_ptr< void > cancel_response)
 

Detailed Description

template<typename ActionT>
class rclcpp_action::Client< ActionT >

Action Client.

This class creates an action client.

Create an instance of this server using rclcpp_action::create_client().

Internally, this class is responsible for:

Member Typedef Documentation

◆ Goal

template<typename ActionT >
using rclcpp_action::Client< ActionT >::Goal = typename ActionT::Goal

◆ Feedback

template<typename ActionT >
using rclcpp_action::Client< ActionT >::Feedback = typename ActionT::Feedback

◆ GoalHandle

template<typename ActionT >
using rclcpp_action::Client< ActionT >::GoalHandle = ClientGoalHandle<ActionT>

◆ Result

template<typename ActionT >
using rclcpp_action::Client< ActionT >::Result = typename GoalHandle::Result

◆ FeedbackCallback

template<typename ActionT >
using rclcpp_action::Client< ActionT >::FeedbackCallback = typename ClientGoalHandle<ActionT>::FeedbackCallback

◆ CancelRequest

template<typename ActionT >
using rclcpp_action::Client< ActionT >::CancelRequest = typename ActionT::CancelGoalService::Request

◆ CancelResponse

template<typename ActionT >
using rclcpp_action::Client< ActionT >::CancelResponse = typename ActionT::CancelGoalService::Response

Constructor & Destructor Documentation

◆ Client()

template<typename ActionT >
rclcpp_action::Client< ActionT >::Client ( 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 rcl_action_client_options_t  client_options = rcl_action_client_get_default_options() 
)
inline

◆ ~Client()

template<typename ActionT >
virtual rclcpp_action::Client< ActionT >::~Client ( )
inlinevirtual

Member Function Documentation

◆ async_send_goal()

template<typename ActionT >
std::shared_future<typename GoalHandle::SharedPtr> rclcpp_action::Client< ActionT >::async_send_goal ( const Goal goal,
FeedbackCallback  callback = nullptr,
bool  ignore_result = false 
)
inline

◆ async_get_result()

template<typename ActionT >
std::shared_future<Result> rclcpp_action::Client< ActionT >::async_get_result ( typename GoalHandle::SharedPtr  goal_handle)
inline

◆ async_cancel_goal()

template<typename ActionT >
std::shared_future<bool> rclcpp_action::Client< ActionT >::async_cancel_goal ( typename GoalHandle::SharedPtr  goal_handle)
inline

◆ async_cancel_all_goals()

template<typename ActionT >
std::shared_future<typename CancelResponse::SharedPtr> rclcpp_action::Client< ActionT >::async_cancel_all_goals ( )
inline

◆ async_cancel_goals_before()

template<typename ActionT >
std::shared_future<typename CancelResponse::SharedPtr> rclcpp_action::Client< ActionT >::async_cancel_goals_before ( const rclcpp::Time stamp)
inline

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