Class GenericClient

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

class GenericClient : public rclcpp_action::ClientBase

Action Generic Client.

This class creates an action generic client.

To create an instance of an action client use rclcpp_action::create_generic_client().

Public Types

using Goal = void*
using GoalRequest = void*
using CancelRequest = typename action_msgs::srv::CancelGoal_Request
using CancelResponse = typename action_msgs::srv::CancelGoal_Response
using WrappedResult = typename GenericClientGoalHandle::WrappedResult
using GoalResponseCallback = std::function<void(typename GenericClientGoalHandle::SharedPtr)>
using FeedbackCallback = typename GenericClientGoalHandle::FeedbackCallback
using ResultCallback = typename GenericClientGoalHandle::ResultCallback
using CancelCallback = std::function<void(CancelResponse::SharedPtr)>
using IntrospectionMessageMembersPtr = const rosidl_typesupport_introspection_cpp::MessageMembers*

Public Functions

GenericClient(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<rcpputils::SharedLibrary> typesupport_lib, const rosidl_action_type_support_t *action_typesupport_handle, const rcl_action_client_options_t &client_options = rcl_action_client_get_default_options())

Construct an action generic client.

This constructs an action generic client, but it will not work until it has been added to a node. Use rclcpp_action::create_generic_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.

  • typesupport_lib[in] A pointer to type support library for the action type

  • action_typesupport_handle[in] the action type support handle

  • client_options[in] Options to pass to the underlying rcl_action::rcl_action_client_t.

std::shared_future<typename GenericClientGoalHandle::SharedPtr> async_send_goal(const Goal goal, size_t goal_size, 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 GenericClientGoalHandle::SharedPtr. If the goal is rejected by an action server, then the future is set to a nullptr.

The goal handle in the future is used to monitor the status of the goal and get the final result.

If callbacks were set in

WARNING this method has inconsistent behaviour and a memory leak bug. If you set the result callback in

To prevent the memory leak, you may call stop_callbacks() explicit. This will delete the self reference.

Parameters:
  • options, you – will receive callbacks, as long as you hold a reference to the shared pointer contained in the returned future, or rclcpp_action::GenericClient is destroyed. Dropping the shared pointer to the goal handle will not cancel the goal. In order to cancel it, you must explicitly call async_cancel_goal.

  • options, the – handle will be self referencing, and you will receive callbacks even though you do not hold a reference to the shared pointer. In this case, the self reference will be deleted if the result callback was received. If there is no result callback, there will be a memory leak.

  • goal[in] The goal.

  • goal_size[in] The size of goal.

  • 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.

std::shared_future<typename GenericClientGoalHandle::SharedPtr> async_send_goal(const GoalRequest goal_request, const SendGoalOptions &options = SendGoalOptions())

Send an action goal request and asynchronously get the result.

Parameters:
  • goal_request[in] The goal request (uuid+goal).

  • 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.

std::shared_future<WrappedResult> async_get_result(typename GenericClientGoalHandle::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.

Returns:

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

std::shared_future<typename CancelResponse::SharedPtr> async_cancel_goal(typename GenericClientGoalHandle::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<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.

void stop_callbacks(typename GenericClientGoalHandle::SharedPtr goal_handle)

Stops the callbacks for the goal in a thread safe way.

This will NOT cancel the goal, it will only stop the callbacks.

After the call to this function, it is guaranteed that there will be no more callbacks from the goal. This is not guaranteed if multiple threads are involved, and the goal_handle is just dropped.

Parameters:

goal_handle[in] The goal were the callbacks shall be stopped

void stop_callbacks(const GoalUUID &goal_id)

Stops the callbacks for the goal in a thread safe way.

For further information see stop_callbacks(typename GenericGoalHandle::SharedPtr goal_handle)

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.

virtual ~GenericClient()
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.