Template Class Client
Defined in File client.hpp
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public rclcpp_action::ClientBase
(Class ClientBase)
Class Documentation
-
template<typename ActionT>
class Client : public rclcpp_action::ClientBase Action Client.
This class creates an action client.
To create an instance of an action client use
rclcpp_action::create_client()
.Internally, this class is responsible for:
coverting between the C++ action type and generic types for
rclcpp_action::ClientBase
, andcalling user callbacks.
Public Types
-
using GoalHandle = ClientGoalHandle<ActionT>
-
using WrappedResult = typename GoalHandle::WrappedResult
-
using GoalResponseCallback = std::function<void(typename GoalHandle::SharedPtr)>
-
using FeedbackCallback = typename GoalHandle::FeedbackCallback
-
using ResultCallback = typename GoalHandle::ResultCallback
-
using CancelCallback = std::function<void(typename CancelResponse::SharedPtr)>
Public Functions
Construct an action client.
This constructs an action client, but it will not work until it has been added to a node. Use
rclcpp_action::create_client()
to both construct and add to a node.- Parameters:
node_base – [in] A pointer to the base interface of a node.
node_graph – [in] A pointer to an interface that allows getting graph information about a node.
node_logging – [in] A pointer to an interface that allows getting a node’s logger.
action_name – [in] The action name.
client_options – [in] Options to pass to the underlying
rcl_action::rcl_action_client_t
.
-
inline std::shared_future<typename GoalHandle::SharedPtr> async_send_goal(const Goal &goal, const SendGoalOptions &options = SendGoalOptions())
Send an action goal and asynchronously get the result.
If the goal is accepted by an action server, the returned future is set to a
ClientGoalHandle
. If the goal is rejected by an action server, then the future is set to anullptr
.The returned goal handle is used to monitor the status of the goal and get the final result. It is valid as long as you hold a reference to the shared pointer or until the rclcpp_action::Client is destroyed at which point the goal status will become UNKNOWN.
- Parameters:
goal – [in] The goal request.
options – [in] Options for sending the goal request. Contains references to callbacks for the goal response (accepted/rejected), feedback, and the final result.
- Returns:
A future that completes when the goal has been accepted or rejected. If the goal is rejected, then the result will be a
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.
- Returns:
A future that is set to the goal result when the goal is finished.
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.
-
inline std::shared_future<typename CancelResponse::SharedPtr> 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.
-
inline std::shared_future<typename CancelResponse::SharedPtr> 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.
-
inline virtual ~Client()
-
struct SendGoalOptions
Options for sending a goal.
This struct is used to pass parameters to the function
async_send_goal
.Public Functions
-
inline SendGoalOptions()
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.
-
inline SendGoalOptions()