Template Class Client

Nested Relationships

Nested Types

Inheritance Relationships

Base Types

  • public rclcpp_action::ClientBase (Class ClientBase)

  • public std::enable_shared_from_this< Client< ActionT > >

Class Documentation

template<typename ActionT>
class Client : public rclcpp_action::ClientBase, public std::enable_shared_from_this<Client<ActionT>>

Public Types

using Goal = typename ActionT::Goal
using Feedback = typename ActionT::Feedback
using Result = typename ActionT::Result
using GoalHandle = ClientGoalHandle<ActionT>
using GoalHandleSharedPtr = typename GoalHandle::SharedPtr
using WrappedResult = typename GoalHandle::WrappedResult
using GoalResponseCallback = std::function<void(typename GoalHandle::SharedPtr)>
using FeedbackCallback = typename GoalHandle::FeedbackCallback
using ResultCallback = typename GoalHandle::ResultCallback
using CancelRequest = typename ActionT::Impl::CancelGoalService::Request
using CancelResponse = typename ActionT::Impl::CancelGoalService::Response
using CancelCallback = std::function<void(typename CancelResponse::SharedPtr)>

Public Functions

inline 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 &options, bool enable_feedback_msg_optimization = false)
inline ~Client()
inline void post_init_setup()
inline virtual bool action_server_is_ready() const
inline std::shared_future<WrappedResult> async_get_result(typename GoalHandle::SharedPtr &goal_handle, ResultCallback result_callback = nullptr)
inline std::shared_future<typename GoalHandle::SharedPtr> async_send_goal(const Goal &goal, const SendGoalOptions &options)
inline std::shared_future<typename CancelResponse::SharedPtr> async_cancel_all_goals(CancelCallback cancel_callback = nullptr)
inline std::shared_future<typename CancelResponse::SharedPtr> async_cancel_goal(typename GoalHandle::SharedPtr goal_handle, CancelCallback cancel_callback = nullptr)
inline std::shared_future<typename CancelResponse::SharedPtr> async_cancel_goals_before(const rclcpp::Time &stamp, CancelCallback cancel_callback = nullptr)
inline void stop_callbacks(typename GoalHandle::SharedPtr goal_handle)
inline void stop_callbacks(const GoalUUID &goal_id)
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))
struct SendGoalOptions

Public Functions

inline SendGoalOptions()
inline void call_feedback_callback(std::shared_ptr<const Feedback> feedback)

Public Members

GoalResponseCallback goal_response_callback
FeedbackCallback feedback_callback
ResultCallback result_callback