AutoAPMS
Resilient Robot Mission Management
|
Helper class that stores contextual information related to a ROS 2 action. More...
#include <auto_apms_util/action_context.hpp>
Public Member Functions | |
ActionContext (rclcpp::Logger logger) | |
Constructor. | |
void | setUp (std::shared_ptr< GoalHandle > goal_handle_ptr) |
Initialize the action context using the current goal handle. | |
void | publishFeedback () |
Publish the feedback written to the internal buffer. | |
void | succeed () |
Terminate the current goal and mark it as succeeded. | |
void | cancel () |
Terminate the current goal and mark it as canceled. | |
void | abort () |
Terminate the current goal and mark it as aborted. | |
void | invalidate () |
Invalidate the goal handle managed by this ActionContext instance. | |
bool | isValid () |
Check if this ActionContext is valid (e.g. is managing a valid action goal handle). | |
std::shared_ptr< GoalHandle > | getGoalHandlePtr () |
Get the goal handle managed by this ActionContext instance. | |
std::shared_ptr< Feedback > | getFeedbackPtr () |
Access the internal action feedback buffer. | |
std::shared_ptr< Result > | getResultPtr () |
Access the internal action result buffer. | |
Helper class that stores contextual information related to a ROS 2 action.
ActionT | Type of the ROS 2 action interface. |
Definition at line 28 of file action_context.hpp.
ActionContext | ( | rclcpp::Logger | logger | ) |
Constructor.
logger | Logger instance of the action's parent node. |
---------------— DEFINITIONS ---------------—
Definition at line 121 of file action_context.hpp.
void setUp | ( | std::shared_ptr< GoalHandle > | goal_handle_ptr | ) |
Initialize the action context using the current goal handle.
goal_handle_ptr | Action goal handle pointer. |
Definition at line 126 of file action_context.hpp.
void publishFeedback | ( | ) |
Publish the feedback written to the internal buffer.
You may access the internal buffer using getFeedbackPtr().
Definition at line 134 of file action_context.hpp.
void succeed | ( | ) |
Terminate the current goal and mark it as succeeded.
The goal will be terminated using the internal actio result buffer, which you may access using getResultPtr().
Definition at line 150 of file action_context.hpp.
void cancel | ( | ) |
Terminate the current goal and mark it as canceled.
The goal will be terminated using the internal actio result buffer, which you may access using getResultPtr().
Definition at line 161 of file action_context.hpp.
void abort | ( | ) |
Terminate the current goal and mark it as aborted.
The goal will be terminated using the internal actio result buffer, which you may access using getResultPtr().
Definition at line 172 of file action_context.hpp.
|
inline |
Invalidate the goal handle managed by this ActionContext instance.
You must initialize the context using a new goal handle before you may call one of publishFeedback(), succeed(), cancel() or abort() again.
Definition at line 183 of file action_context.hpp.
|
inline |
Check if this ActionContext is valid (e.g. is managing a valid action goal handle).
true
if the context is ok, false
otherwise. Definition at line 189 of file action_context.hpp.
std::shared_ptr< typename ActionContext< ActionT >::GoalHandle > getGoalHandlePtr | ( | ) |
Get the goal handle managed by this ActionContext instance.
Definition at line 195 of file action_context.hpp.
|
inline |
Access the internal action feedback buffer.
Definition at line 206 of file action_context.hpp.
|
inline |
Access the internal action result buffer.
Definition at line 212 of file action_context.hpp.