AutoAPMS
Resilient Robot Mission Management
Loading...
Searching...
No Matches
ActionClientWrapper< ActionT > Class Template Reference

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

#include <auto_apms_util/action_client_wrapper.hpp>

Public Member Functions

 ActionClientWrapper (rclcpp::Node::SharedPtr node_ptr, const std::string &action_name)
 ActionClientWrapper constructor.
 
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.
 
bool syncCancelLastGoal (const std::chrono::seconds response_timeout=std::chrono::seconds{3})
 Request to cancel the most recent goal.
 
ClientGoalHandle::SharedPtr getActiveGoalHandle ()
 Get the goal handle of the currently active goal.
 
std::shared_ptr< const Feedback > getFeedback ()
 Get the most recent feedback.
 

Static Public Member Functions

static ActionGoalStatus getGoalStatus (const ResultFuture &future)
 Determine the status of a specific goal by evaluating the corresponding ActionClientWrapper::ResultFuture.
 

Detailed Description

template<typename ActionT>
class auto_apms_util::ActionClientWrapper< ActionT >

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

Definition at line 54 of file action_client_wrapper.hpp.

Constructor & Destructor Documentation

◆ ActionClientWrapper()

template<typename ActionT>
ActionClientWrapper ( rclcpp::Node::SharedPtr node_ptr,
const std::string & action_name )

ActionClientWrapper constructor.

Parameters
node_ptrShared pointer to the node.
action_nameName of the corresponding action.

Definition at line 131 of file action_client_wrapper.hpp.

Member Function Documentation

◆ syncSendGoal()

template<typename ActionT>
ActionClientWrapper< ActionT >::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
goalGoal of the action that will be sent to the server
optionsGoal options to be forwarded
server_timeoutTimeout for waiting for the action server to be discovered
response_timeoutTimeout for waiting for a goal response from the server
Returns
Shared future that completes when the action finishes, holding the result. The result is nullptr if the goal was rejected.
Exceptions
std::runtime_errorif sending the goal fails.

Definition at line 140 of file action_client_wrapper.hpp.

◆ syncCancelLastGoal()

template<typename ActionT>
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_timeoutTimeout for waiting for a cancel response from the server
Returns
true if the last goal was cancelled successfully, false if request was denied.
Exceptions
std::runtime_errorif cancelation failed.

Definition at line 190 of file action_client_wrapper.hpp.

◆ getGoalStatus()

template<typename ActionT>
ActionGoalStatus getGoalStatus ( const ResultFuture & future)
static

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

Parameters
futureActionClientWrapper::ResultFuture corresponding to the goal whose status is to be retrieved
Returns
auto_apms::ActionGoalStatus value that indicates whether the goal was rejected, is currently being processed or has completed.
Exceptions
std::runtime_errorif future is invalid.

Definition at line 224 of file action_client_wrapper.hpp.

◆ getActiveGoalHandle()

template<typename ActionT>
ActionClientWrapper< ActionT >::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.

Definition at line 239 of file action_client_wrapper.hpp.

◆ getFeedback()

template<typename ActionT>
std::shared_ptr< const typename ActionClientWrapper< ActionT >::Feedback > getFeedback ( )

Get the most recent feedback.

Returns
Shared pointer of the feeback.

Definition at line 245 of file action_client_wrapper.hpp.


The documentation for this class was generated from the following file: