Template Class ActionContext

Class Documentation

template<typename ActionT>
class ActionContext

Helper class that stores contextual information related to a ROS 2 action.

Template Parameters:

ActionT – Type of the ROS 2 action interface.

Public Types

using Type = ActionT
using Goal = typename ActionT::Goal
using Feedback = typename ActionT::Feedback
using Result = typename ActionT::Result
using GoalHandle = rclcpp_action::ServerGoalHandle<ActionT>

Public Functions

ActionContext(rclcpp::Logger logger)

Constructor.

—————&#8212; DEFINITIONS —————&#8212;

Parameters:

logger – Logger instance of the action’s parent node.

void setUp(std::shared_ptr<GoalHandle> goal_handle_ptr)

Initialize the action context using the current goal handle.

Parameters:

goal_handle_ptr – Action goal handle pointer.

void publishFeedback()

Publish the feedback written to the internal buffer.

You may access the internal buffer using getFeedbackPtr().

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().

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().

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().

inline void invalidate()

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.

inline bool isValid()

Check if this ActionContext is valid (e.g. is managing a valid action goal handle).

Returns:

true if the context is ok, false otherwise.

std::shared_ptr<GoalHandle> getGoalHandlePtr()

Get the goal handle managed by this ActionContext instance.

Returns:

Current action goal handle.

inline std::shared_ptr<Feedback> getFeedbackPtr()

Access the internal action feedback buffer.

Returns:

Shared pointer of the feedback data structure.

inline std::shared_ptr<Result> getResultPtr()

Access the internal action result buffer.

Returns:

Shared pointer of the result data structure.