Template Class Client< ros_babel_fish::impl::BabelFishAction >

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public rclcpp_action::ClientBase

Class Documentation

template<>
class Client<ros_babel_fish::impl::BabelFishAction> : public rclcpp_action::ClientBase

Public Types

using GoalHandle = rclcpp_action::ClientGoalHandle<ros_babel_fish::impl::BabelFishAction>
using WrappedResult = GoalHandle::WrappedResult
using GoalResponseCallback = std::function<void(typename GoalHandle::SharedPtr)>
using FeedbackCallback = GoalHandle::FeedbackCallback
using ResultCallback = GoalHandle::ResultCallback
using CancelRequest = ros_babel_fish::CompoundMessage
using CancelResponse = ros_babel_fish::CompoundMessage
using CancelCallback = std::function<void(CancelResponse)>

Public 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, std::shared_ptr<const ros_babel_fish::ActionTypeSupport> type_support, const rcl_action_client_options_t &client_options = rcl_action_client_get_default_options())
ros_babel_fish::CompoundMessage create_goal() const
std::shared_future<GoalHandle::SharedPtr> async_send_goal(const ros_babel_fish::CompoundMessage &goal, const SendGoalOptions &options = {})
std::shared_future<WrappedResult> async_get_result(typename GoalHandle::SharedPtr goal_handle, ResultCallback result_callback = nullptr)

Asynchronously get the result for an active goal.

Throws:

exceptions::UnknownGoalHandleError – If the goal unknown or already reached a terminal state, or if there was an error requesting the result.

Parameters:
  • goal_handle[in] The goal handle for which to get the result.

  • result_callback[in] Optional callback that is called when the result is received. Will overwrite any result callback specified in async_send_goal!

Returns:

A future that is set to the goal result when the goal is finished.

std::shared_future<CancelResponse> async_cancel_goal(GoalHandle::SharedPtr goal_handle, CancelCallback cancel_callback = nullptr)

Asynchronously request a goal be canceled.

Throws:

exceptions::UnknownGoalHandleError – If the goal is unknown or already reached a terminal state.

Parameters:
  • goal_handle[in] The goal handle requesting to be canceled.

  • cancel_callback[in] Optional callback that is called when the response is received. The callback takes one parameter: a shared pointer to the CancelResponse message.

Returns:

A future to a CancelResponse message that is set when the request has been acknowledged by an action server. See action_msgs/CancelGoal.srv.

std::shared_future<CancelResponse> async_cancel_all_goals(CancelCallback cancel_callback = nullptr)

Asynchronously request for all goals to be canceled.

Parameters:

cancel_callback[in] Optional callback that is called when the response is received. The callback takes one parameter: a shared pointer to the CancelResponse message.

Returns:

A future to a CancelResponse message that is set when the request has been acknowledged by an action server. See action_msgs/CancelGoal.srv.

std::shared_future<CancelResponse> async_cancel_goals_before(const rclcpp::Time &stamp, CancelCallback cancel_callback = nullptr)

Asynchronously request all goals at or before a specified time be canceled.

Parameters:
  • stamp[in] The timestamp for the cancel goal request.

  • cancel_callback[in] Optional callback that is called when the response is received. The callback takes one parameter: a shared pointer to the CancelResponse message.

Returns:

A future to a CancelResponse message that is set when the request has been acknowledged by an action server. See action_msgs/CancelGoal.srv.

Protected Functions

std::shared_ptr<void> create_goal_response() const override
std::shared_ptr<void> create_result_response() const override
std::shared_ptr<void> create_cancel_response() const override
std::shared_ptr<void> create_feedback_message() const override
void handle_feedback_message(std::shared_ptr<void> message) override
std::shared_ptr<void> create_status_message() const override
void handle_status_message(std::shared_ptr<void> message) override
void make_result_aware(GoalHandle::SharedPtr goal_handle)
std::shared_future<CancelResponse> async_cancel(CancelRequest cancel_request, CancelCallback cancel_callback = nullptr)
template<>
struct SendGoalOptions

Options for sending a goal.

This struct is used to pass parameters to the function async_send_goal.

Public Members

GoalResponseCallback goal_response_callback

Function called when the goal is accepted or rejected.

Takes a single argument that is a goal handle shared pointer. If the goal is accepted, then the pointer points to a valid goal handle. If the goal is rejected, then pointer has the value nullptr.

FeedbackCallback feedback_callback

Function called whenever feedback is received for the goal.

ResultCallback result_callback

Function called when the result for the goal is received.