Template Class ActionWrapper

Class Documentation

template<typename ActionT>
class ActionWrapper

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.

Public Types

using Params = action_wrapper_params::Params
using ParamListener = action_wrapper_params::ParamListener
using Status = ActionStatus
using ActionContextType = ActionContext<ActionT>
using Goal = typename ActionContextType::Goal
using Feedback = typename ActionContextType::Feedback
using Result = typename ActionContextType::Result
using GoalHandle = typename ActionContextType::GoalHandle

Public Functions

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

Constructor.

Parameters:
  • 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.

explicit ActionWrapper(const std::string &action_name, rclcpp::Node::SharedPtr node_ptr)

Constructor.

Parameters:
  • action_name – Name of the action.

  • node_ptr – ROS 2 node pointer.

explicit ActionWrapper(const std::string &action_name, const rclcpp::NodeOptions &options)

Constructor.

Parameters:
  • action_name – Name of the action.

  • options – ROS 2 node options used for initialization.

rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() const

Protected Attributes

rclcpp::Node::SharedPtr node_ptr_
std::shared_ptr<ActionContextType> action_context_ptr_
const ParamListener param_listener_