Template Class ActionClientWrapper

Class Documentation

template<typename ActionT>
class ActionClientWrapper

Convenience wrapper for a rclcpp_action::Client that introduces synchronous goal handling functions.

Public Types

using Goal = typename ActionT::Goal
using SendGoalOptions = typename rclcpp_action::Client<ActionT>::SendGoalOptions
using Feedback = typename ActionT::Feedback
using Result = typename ActionT::Result
using ClientGoalHandle = rclcpp_action::ClientGoalHandle<ActionT>
using WrappedResultSharedPtr = std::shared_ptr<typename ClientGoalHandle::WrappedResult>
using ResultFuture = std::shared_future<WrappedResultSharedPtr>

Public Functions

ActionClientWrapper(rclcpp::Node::SharedPtr node_ptr, const std::string &action_name)

ActionClientWrapper constructor.

Parameters:
  • node_ptr – Shared pointer to the node.

  • action_name – Name of the corresponding action.

ResultFuture syncSendGoal(const Goal &goal = Goal{}, const SendGoalOptions &options = SendGoalOptions{}, const std::chrono::seconds server_timeout = std::chrono::seconds{3}, const std::chrono::seconds response_timeout = std::chrono::seconds{3})

Send a goal to the action and synchronously wait for the response.

Parameters:
  • goal – Goal of the action that will be sent to the server

  • options – Goal options to be forwarded

  • server_timeout – Timeout for waiting for the action server to be discovered

  • response_timeout – Timeout for waiting for a goal response from the server

Throws:

std::runtime_error – if sending the goal fails.

Returns:

Shared future that completes when the action finishes, holding the result. The result is nullptr if the goal was rejected.

bool syncCancelLastGoal(const std::chrono::seconds response_timeout = std::chrono::seconds{3})

Request to cancel the most recent goal.

This method is synchronous, meaning that it blocks until the cancelation result is received.

Parameters:

response_timeout – Timeout for waiting for a cancel response from the server

Throws:

std::runtime_error – if cancelation failed.

Returns:

true if the last goal was cancelled successfully, false if request was denied.

ClientGoalHandle::SharedPtr getActiveGoalHandle()

Get the goal handle of the currently active goal.

Returns:

Shared pointer of the active goal handle or nullptr, if there is no active goal.

std::shared_ptr<const Feedback> getFeedback()

Get the most recent feedback.

Returns:

Shared pointer of the feeback.

Public Static Functions

static ActionGoalStatus getGoalStatus(const ResultFuture &future)

Determine the status of a specific goal by evaluating the corresponding ActionClientWrapper::ResultFuture.

Parameters:

future – ActionClientWrapper::ResultFuture corresponding to the goal whose status is to be retrieved

Throws:

std::runtime_error – if future is invalid.

Returns:

auto_apms::ActionGoalStatus value that indicates whether the goal was rejected, is currently being processed or has completed.