AutoAPMS
Resilient Robot Mission Management
|
Generic template class for executing a PX4 mode implementing the interface of a standard ROS 2 action. More...
#include <auto_apms_px4/mode_executor.hpp>
Private Member Functions | |
bool | onGoalRequest (std::shared_ptr< const Goal > goal_ptr) override final |
Callback for handling an incoming action goal request. | |
bool | onCancelRequest (std::shared_ptr< const Goal > goal_ptr, std::shared_ptr< Result > result_ptr) override final |
Callback for handling an incoming cancel request. | |
auto_apms_util::ActionStatus | cancelGoal (std::shared_ptr< const Goal > goal_ptr, std::shared_ptr< Result > result_ptr) override final |
Callback that executes work asynchronously when the goal is cancelling. | |
auto_apms_util::ActionStatus | executeGoal (std::shared_ptr< const Goal > goal_ptr, std::shared_ptr< Feedback > feedback_ptr, std::shared_ptr< Result > result_ptr) override final |
Callback that executes work asynchronously when the goal is executing. | |
Additional Inherited Members | |
Public Member Functions inherited from ActionWrapper< ActionT > | |
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. | |
Generic template class for executing a PX4 mode implementing the interface of a standard ROS 2 action.
The modes to be executed must be registered with the PX4 autopilot server before any action goals are sent. By default, only the standard PX4 modes may be executed, but the user may also implement custom modes using ModeBase. Refer to ModeExecutorFactory if you want to set up a ROS 2 node for executing your custom modes.
To register a ROS 2 node component that is able to execute for example the land mode when requested, the corresponding executor is implemented as follows:
auto_apms_px4
comes with ROS 2 node components for the most common standard modes and they work out of the box.ActionT | Type of the ROS 2 action. |
Definition at line 84 of file mode_executor.hpp.
|
finaloverrideprivatevirtual |
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 from ActionWrapper< ActionT >.
Definition at line 265 of file mode_executor.hpp.
|
finaloverrideprivatevirtual |
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 from ActionWrapper< ActionT >.
Definition at line 275 of file mode_executor.hpp.
|
finaloverrideprivatevirtual |
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 from ActionWrapper< ActionT >.
Definition at line 289 of file mode_executor.hpp.
|
finaloverrideprivatevirtual |
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. |
Implements ActionWrapper< ActionT >.
Definition at line 308 of file mode_executor.hpp.