AutoAPMS
Resilient Robot Mission Management
Loading...
Searching...
No Matches
Task< ActionT > Class Template Referenceabstract

#include <auto_apms_core/task.hpp>

Inheritance diagram for Task< ActionT >:

Public Types

using Status = TaskStatus
 
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 Member Functions

 Task (const std::string &name, rclcpp::Node::SharedPtr node_ptr, std::shared_ptr< ActionContextType > action_context_ptr, std::chrono::milliseconds execution_interval=DEFAULT_VALUE_EXECUTION_INTERVAL, std::chrono::milliseconds feedback_interval=DEFAULT_VALUE_FEEDBACK_INTERVAL)
 
 Task (const std::string &name, rclcpp::Node::SharedPtr node_ptr, std::chrono::milliseconds execution_interval=DEFAULT_VALUE_EXECUTION_INTERVAL, std::chrono::milliseconds feedback_interval=DEFAULT_VALUE_FEEDBACK_INTERVAL)
 
 Task (const std::string &name, const rclcpp::NodeOptions &options, std::chrono::milliseconds execution_interval=DEFAULT_VALUE_EXECUTION_INTERVAL, std::chrono::milliseconds feedback_interval=DEFAULT_VALUE_FEEDBACK_INTERVAL)
 
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface () const
 

Static Public Attributes

static constexpr std::chrono::milliseconds DEFAULT_VALUE_EXECUTION_INTERVAL { 10 }
 
static constexpr std::chrono::milliseconds DEFAULT_VALUE_FEEDBACK_INTERVAL { 200 }
 
static constexpr char PARAM_NAME_FEEDBACK_INTERVAL [] = "feedback_interval_ms"
 

Protected Attributes

rclcpp::Node::SharedPtr node_ptr_
 
std::shared_ptr< ActionContextTypeaction_context_ptr_
 

Detailed Description

template<typename ActionT>
class auto_apms_core::Task< ActionT >

Generic base class for robot actions.

A auto_apms_core::Task is esentially a wrapper for a rclcpp_action::Server providing convenient extension points.

Definition at line 51 of file task.hpp.

Member Typedef Documentation

◆ Status

template<typename ActionT >
using Status = TaskStatus

Definition at line 54 of file task.hpp.

◆ ActionContextType

template<typename ActionT >
using ActionContextType = ActionContext<ActionT>

Definition at line 55 of file task.hpp.

◆ Goal

template<typename ActionT >
using Goal = typename ActionContextType::Goal

Definition at line 56 of file task.hpp.

◆ Feedback

template<typename ActionT >
using Feedback = typename ActionContextType::Feedback

Definition at line 57 of file task.hpp.

◆ Result

template<typename ActionT >
using Result = typename ActionContextType::Result

Definition at line 58 of file task.hpp.

◆ GoalHandle

template<typename ActionT >
using GoalHandle = typename ActionContextType::GoalHandle

Definition at line 59 of file task.hpp.

Constructor & Destructor Documentation

◆ Task() [1/3]

template<class ActionT >
Task ( const std::string & name,
rclcpp::Node::SharedPtr node_ptr,
std::shared_ptr< ActionContextType > action_context_ptr,
std::chrono::milliseconds execution_interval = DEFAULT_VALUE_EXECUTION_INTERVAL,
std::chrono::milliseconds feedback_interval = DEFAULT_VALUE_FEEDBACK_INTERVAL )
explicit

Parameters

Definition at line 117 of file task.hpp.

◆ Task() [2/3]

template<class ActionT >
Task ( const std::string & name,
rclcpp::Node::SharedPtr node_ptr,
std::chrono::milliseconds execution_interval = DEFAULT_VALUE_EXECUTION_INTERVAL,
std::chrono::milliseconds feedback_interval = DEFAULT_VALUE_FEEDBACK_INTERVAL )
explicit

Definition at line 138 of file task.hpp.

◆ Task() [3/3]

template<class ActionT >
Task ( const std::string & name,
const rclcpp::NodeOptions & options,
std::chrono::milliseconds execution_interval = DEFAULT_VALUE_EXECUTION_INTERVAL,
std::chrono::milliseconds feedback_interval = DEFAULT_VALUE_FEEDBACK_INTERVAL )
explicit

Definition at line 146 of file task.hpp.

Member Function Documentation

◆ get_node_base_interface()

template<class ActionT >
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface ( ) const

Definition at line 154 of file task.hpp.

Member Data Documentation

◆ DEFAULT_VALUE_EXECUTION_INTERVAL

template<typename ActionT >
std::chrono::milliseconds DEFAULT_VALUE_EXECUTION_INTERVAL { 10 }
staticconstexpr

Definition at line 61 of file task.hpp.

◆ DEFAULT_VALUE_FEEDBACK_INTERVAL

template<typename ActionT >
std::chrono::milliseconds DEFAULT_VALUE_FEEDBACK_INTERVAL { 200 }
staticconstexpr

Definition at line 62 of file task.hpp.

◆ PARAM_NAME_FEEDBACK_INTERVAL

template<typename ActionT >
char PARAM_NAME_FEEDBACK_INTERVAL[] = "feedback_interval_ms"
staticconstexpr

Definition at line 63 of file task.hpp.

◆ node_ptr_

template<typename ActionT >
rclcpp::Node::SharedPtr node_ptr_
protected

Definition at line 106 of file task.hpp.

◆ action_context_ptr_

template<typename ActionT >
std::shared_ptr<ActionContextType> action_context_ptr_
protected

Definition at line 107 of file task.hpp.


The documentation for this class was generated from the following file: