Template Class AbstractActionBase

Nested Relationships

Nested Types

Class Documentation

template<typename Action, typename Execution>
class AbstractActionBase

Base class for managing multiple concurrent executions.

Place the implementation specific code into AbstractActionBase::runImpl. Also it is required, that you define MyExecution::Ptr as a shared pointer for your execution.

Template Parameters:

Public Types

typedef std::shared_ptr<AbstractActionBase> Ptr
typedef rclcpp_action::ServerGoalHandle<Action> GoalHandle
typedef std::shared_ptr<GoalHandle> GoalHandlePtr

Public Functions

inline AbstractActionBase(const rclcpp::Node::SharedPtr &node, const std::string &name, const mbf_utility::RobotInformation::ConstPtr &robot_info)

Construct a new AbstractActionBase.

Parameters:
inline virtual ~AbstractActionBase()
inline virtual void start(const GoalHandlePtr &goal_handle, typename Execution::Ptr execution_ptr)
inline virtual void cancel(GoalHandlePtr goal_handle)
inline virtual void runImpl(const GoalHandlePtr &goal_handle, Execution &execution)
inline virtual void run(ConcurrencySlot &slot)
inline virtual void cancelAll()

Protected Types

typedef std::unordered_map<uint8_t, ConcurrencySlot> ConcurrencyMap

Protected Attributes

rclcpp::Node::SharedPtr node_
const std::string name_
mbf_utility::RobotInformation::ConstPtr robot_info_
ConcurrencyMap concurrency_slots_
std::mutex slot_map_mtx_
struct ConcurrencySlot

POD holding info for one execution.

Public Functions

inline ConcurrencySlot()

Public Members

Execution::Ptr execution
std::thread *thread_ptr

Owned pointer to a thread.

GoalHandlePtr goal_handle
bool in_use