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

#include <auto_apms_core/action_client.hpp>

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 Member Functions

 ActionClientWrapper (rclcpp::Node &node, const std::string &action_name)
 
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 })
 
bool syncCancelLastGoal (const std::chrono::seconds response_timeout=std::chrono::seconds{ 3 })
 
ClientGoalHandle::SharedPtr getActiveGoalHandle ()
 
std::shared_ptr< const FeedbackgetFeedback ()
 

Static Public Member Functions

static ActionGoalStatus getGoalStatus (const ResultFuture &future)
 

Detailed Description

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

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

Definition at line 45 of file action_client.hpp.

Member Typedef Documentation

◆ Goal

template<typename ActionT >
using Goal = typename ActionT::Goal

Definition at line 48 of file action_client.hpp.

◆ SendGoalOptions

template<typename ActionT >
using SendGoalOptions = typename rclcpp_action::Client<ActionT>::SendGoalOptions

Definition at line 49 of file action_client.hpp.

◆ Feedback

template<typename ActionT >
using Feedback = typename ActionT::Feedback

Definition at line 50 of file action_client.hpp.

◆ Result

template<typename ActionT >
using Result = typename ActionT::Result

Definition at line 51 of file action_client.hpp.

◆ ClientGoalHandle

template<typename ActionT >
using ClientGoalHandle = rclcpp_action::ClientGoalHandle<ActionT>

Definition at line 52 of file action_client.hpp.

◆ WrappedResultSharedPtr

template<typename ActionT >
using WrappedResultSharedPtr = std::shared_ptr<typename ClientGoalHandle::WrappedResult>

Definition at line 53 of file action_client.hpp.

◆ ResultFuture

template<typename ActionT >
using ResultFuture = std::shared_future<WrappedResultSharedPtr>

Definition at line 54 of file action_client.hpp.

Constructor & Destructor Documentation

◆ ActionClientWrapper()

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

Constructor.

Parameters
nodeNode reference. This instance doesn't own the node
action_nameName of the corresponding action

Definition at line 121 of file action_client.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 131 of file action_client.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 186 of file action_client.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 223 of file action_client.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 241 of file action_client.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 247 of file action_client.hpp.


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