AutoAPMS
Resilient Robot Mission Management
Loading...
Searching...
No Matches
ActionWrapper< ActionT > Class Template Referenceabstract

Generic base class for implementing robot skills using the ROS 2 action concept. More...

#include <auto_apms_util/action_wrapper.hpp>

Inheritance diagram for ActionWrapper< ActionT >:

Public Member Functions

 ActionWrapper (const std::string &action_name, rclcpp::Node::SharedPtr node_ptr, std::shared_ptr< ActionContextType > action_context_ptr)
 Constructor.
 
 ActionWrapper (const std::string &action_name, rclcpp::Node::SharedPtr node_ptr)
 Constructor.
 
 ActionWrapper (const std::string &action_name, const rclcpp::NodeOptions &options)
 Constructor.
 

Private Member Functions

virtual bool onGoalRequest (std::shared_ptr< const Goal > goal_ptr)
 Callback for handling an incoming action goal request.
 
virtual void setInitialResult (std::shared_ptr< const Goal > goal_ptr, std::shared_ptr< Result > result_ptr)
 Configure the initial action result that is set once a goal is accepted.
 
virtual bool onCancelRequest (std::shared_ptr< const Goal > goal_ptr, std::shared_ptr< Result > result_ptr)
 Callback for handling an incoming cancel request.
 
virtual Status cancelGoal (std::shared_ptr< const Goal > goal_ptr, std::shared_ptr< Result > result_ptr)
 Callback that executes work asynchronously when the goal is cancelling.
 
virtual Status executeGoal (std::shared_ptr< const Goal > goal_ptr, std::shared_ptr< Feedback > feedback_ptr, std::shared_ptr< Result > result_ptr)=0
 Callback that executes work asynchronously when the goal is executing.
 

Detailed Description

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

Generic base class for implementing robot skills using the ROS 2 action concept.

This wraps a rclcpp_action::Server and provides convenient extension points for the user. You must implement the pure virtual method ActionWrapper::executeGoal when inheriting from this class.

Note
ActionWrapper::executeGoal and ActionWrapper::cancelGoal are intended to work asynchronously. This means that a timer repeatedly invokes these callbacks until the returned status is either ActionStatus::SUCCESS or ActionStatus::FAILURE.

Definition at line 57 of file action_wrapper.hpp.

Constructor & Destructor Documentation

◆ ActionWrapper() [1/3]

template<class ActionT>
ActionWrapper ( const std::string & action_name,
rclcpp::Node::SharedPtr node_ptr,
std::shared_ptr< ActionContextType > action_context_ptr )
explicit

Constructor.

Parameters
action_nameName of the action.
node_ptrROS 2 node pointer.
action_context_ptrPointer to a shared instance of the associated action context.

Definition at line 178 of file action_wrapper.hpp.

◆ ActionWrapper() [2/3]

template<class ActionT>
ActionWrapper ( const std::string & action_name,
rclcpp::Node::SharedPtr node_ptr )
explicit

Constructor.

Parameters
action_nameName of the action.
node_ptrROS 2 node pointer.

Definition at line 193 of file action_wrapper.hpp.

◆ ActionWrapper() [3/3]

template<class ActionT>
ActionWrapper ( const std::string & action_name,
const rclcpp::NodeOptions & options )
explicit

Constructor.

Parameters
action_nameName of the action.
optionsROS 2 node options used for initialization.

Definition at line 199 of file action_wrapper.hpp.

Member Function Documentation

◆ onGoalRequest()

template<class ActionT>
bool onGoalRequest ( std::shared_ptr< const Goal > goal_ptr)
privatevirtual

Callback for handling an incoming action goal request.

Implementation specific callbacks

By default, all goals are accepted.

Parameters
goal_ptrGoal request.
Returns
true for accepting the request and false for rejecting it.

Reimplemented in ModeExecutor< ActionT >, ModeExecutor< auto_apms_interfaces::action::EnableHold >, ModeExecutor< auto_apms_interfaces::action::Land >, ModeExecutor< auto_apms_interfaces::action::Mission >, ModeExecutor< auto_apms_interfaces::action::RTL >, and ModeExecutor< auto_apms_interfaces::action::Takeoff >.

Definition at line 211 of file action_wrapper.hpp.

◆ setInitialResult()

template<class ActionT>
void setInitialResult ( std::shared_ptr< const Goal > goal_ptr,
std::shared_ptr< Result > result_ptr )
privatevirtual

Configure the initial action result that is set once a goal is accepted.

By default, the respective type defaults are used.

Parameters
goal_ptrAccepted action goal.
result_ptrShared action result to be modified.

Definition at line 218 of file action_wrapper.hpp.

◆ onCancelRequest()

template<class ActionT>
bool onCancelRequest ( std::shared_ptr< const Goal > goal_ptr,
std::shared_ptr< Result > result_ptr )
privatevirtual

Callback for handling an incoming cancel request.

By default, cancelling a goal is always accepted.

Parameters
goal_ptrOriginal goal of the action to be canceled.
result_ptrShared action result to be modified.
Returns
true for accepting the request and false for rejecting it.

Reimplemented in ModeExecutor< ActionT >, ModeExecutor< auto_apms_interfaces::action::EnableHold >, ModeExecutor< auto_apms_interfaces::action::Land >, ModeExecutor< auto_apms_interfaces::action::Mission >, ModeExecutor< auto_apms_interfaces::action::RTL >, and ModeExecutor< auto_apms_interfaces::action::Takeoff >.

Definition at line 225 of file action_wrapper.hpp.

◆ cancelGoal()

template<class ActionT>
ActionStatus cancelGoal ( std::shared_ptr< const Goal > goal_ptr,
std::shared_ptr< Result > result_ptr )
privatevirtual

Callback that executes work asynchronously when the goal is cancelling.

By default, this callback does nothing.

You must return ActionStatus::RUNNING, if this callback's work is not done yet and it should be invoked again. Otherwise, return ActionStatus::SUCCESS or ActionStatus::FAILURE to cancel respectively abort the goal.

Parameters
goal_ptrOriginal goal of the action that is being canceled.
result_ptrShared action result to be modified.
Returns
Status of the cancellation routine.

Reimplemented in ModeExecutor< ActionT >, ModeExecutor< auto_apms_interfaces::action::EnableHold >, ModeExecutor< auto_apms_interfaces::action::Land >, ModeExecutor< auto_apms_interfaces::action::Mission >, ModeExecutor< auto_apms_interfaces::action::RTL >, and ModeExecutor< auto_apms_interfaces::action::Takeoff >.

Definition at line 233 of file action_wrapper.hpp.

◆ executeGoal()

template<typename ActionT>
virtual Status executeGoal ( std::shared_ptr< const Goal > goal_ptr,
std::shared_ptr< Feedback > feedback_ptr,
std::shared_ptr< Result > result_ptr )
privatepure virtual

Callback that executes work asynchronously when the goal is executing.

You must return ActionStatus::RUNNING, if this callback's work is not done yet and it should be invoked again. Otherwise, return ActionStatus::SUCCESS or ActionStatus::FAILURE to succeed respectively abort the goal.

Parameters
goal_ptrOriginal goal of the action that is being executed.
feedback_ptrShared action feedback that is published according to the configured feedback rate.
result_ptrShared action result to be modified.
Returns
Status of the execution routine.

Implemented in ModeExecutor< ActionT >, ModeExecutor< auto_apms_interfaces::action::EnableHold >, ModeExecutor< auto_apms_interfaces::action::Land >, ModeExecutor< auto_apms_interfaces::action::Mission >, ModeExecutor< auto_apms_interfaces::action::RTL >, and ModeExecutor< auto_apms_interfaces::action::Takeoff >.


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