AutoAPMS
Resilient Robot Mission Management
|
Generic base class for implementing robot skills using the ROS 2 action concept. More...
#include <auto_apms_util/action_wrapper.hpp>
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. | |
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.
Definition at line 57 of file action_wrapper.hpp.
|
explicit |
Constructor.
action_name | Name of the action. |
node_ptr | ROS 2 node pointer. |
action_context_ptr | Pointer to a shared instance of the associated action context. |
Definition at line 178 of file action_wrapper.hpp.
|
explicit |
Constructor.
action_name | Name of the action. |
node_ptr | ROS 2 node pointer. |
Definition at line 193 of file action_wrapper.hpp.
|
explicit |
Constructor.
action_name | Name of the action. |
options | ROS 2 node options used for initialization. |
Definition at line 199 of file action_wrapper.hpp.
|
privatevirtual |
Callback for handling an incoming action goal request.
Implementation specific callbacks
By default, all goals are accepted.
goal_ptr | Goal request. |
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.
|
privatevirtual |
Configure the initial action result that is set once a goal is accepted.
By default, the respective type defaults are used.
goal_ptr | Accepted action goal. |
result_ptr | Shared action result to be modified. |
Definition at line 218 of file action_wrapper.hpp.
|
privatevirtual |
Callback for handling an incoming cancel request.
By default, cancelling a goal is always accepted.
goal_ptr | Original goal of the action to be canceled. |
result_ptr | Shared action result to be modified. |
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.
|
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.
goal_ptr | Original goal of the action that is being canceled. |
result_ptr | Shared action result to be modified. |
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.
|
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.
goal_ptr | Original goal of the action that is being executed. |
feedback_ptr | Shared action feedback that is published according to the configured feedback rate. |
result_ptr | Shared action result to be modified. |
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 >.