#include <RobotTask.h>

Classes | |
| class | TaskResult |
Static Public Attributes | |
| static const int32_t | FAIL = 1 |
| static const int32_t | PLAN = -1 |
| static const int32_t | SUCCESS = 0 |
Protected Types | |
| typedef RobotTaskFeedback | FEEDBACK |
| typedef actionlib::MGActionServer < RobotTaskAction > ::GoalHandle | GOAL |
| typedef RobotTaskResult | RESULT |
| typedef actionlib::MGActionServer < RobotTaskAction > | Server |
Protected Member Functions | |
| void | abstract_task (GOAL goal_handle) |
| void | finish (GOAL goalH, const int32_t &success, const std::string &description, const string &plan, bool AbortForUnsuccess=true) |
| bool | isPreempt () |
| RobotTask (string name) | |
| void | sleep (long millisec) |
| virtual RobotTask::TaskResult | task (const string &name, const string &uid, Arguments &args)=0 |
| virtual | ~RobotTask () |
Protected Attributes | |
| FEEDBACK | _feedback |
| string | _name |
| ros::NodeHandle | _node |
| RESULT | _result |
| Server | _server |
| std::map< boost::thread::id, GOAL > | goalsByThread |
Definition at line 42 of file RobotTask.h.
typedef RobotTaskFeedback robot_task::RobotTask::FEEDBACK [protected] |
Definition at line 49 of file RobotTask.h.
typedef actionlib::MGActionServer<RobotTaskAction>::GoalHandle robot_task::RobotTask::GOAL [protected] |
Definition at line 56 of file RobotTask.h.
typedef RobotTaskResult robot_task::RobotTask::RESULT [protected] |
Definition at line 50 of file RobotTask.h.
typedef actionlib::MGActionServer<RobotTaskAction> robot_task::RobotTask::Server [protected] |
Definition at line 57 of file RobotTask.h.
| robot_task::RobotTask::RobotTask | ( | string | name | ) | [inline, protected] |
Definition at line 67 of file RobotTask.h.
| virtual robot_task::RobotTask::~RobotTask | ( | ) | [inline, protected, virtual] |
Definition at line 76 of file RobotTask.h.
| void robot_task::RobotTask::abstract_task | ( | GOAL | goal_handle | ) | [inline, protected] |
Definition at line 161 of file RobotTask.h.
| void robot_task::RobotTask::finish | ( | GOAL | goalH, |
| const int32_t & | success, | ||
| const std::string & | description, | ||
| const string & | plan, | ||
| bool | AbortForUnsuccess = true |
||
| ) | [inline, protected] |
Definition at line 85 of file RobotTask.h.
| bool robot_task::RobotTask::isPreempt | ( | ) | [inline, protected] |
Definition at line 143 of file RobotTask.h.
| void robot_task::RobotTask::sleep | ( | long | millisec | ) | [inline, protected] |
Definition at line 153 of file RobotTask.h.
| virtual RobotTask::TaskResult robot_task::RobotTask::task | ( | const string & | name, |
| const string & | uid, | ||
| Arguments & | args | ||
| ) | [protected, pure virtual] |
FEEDBACK robot_task::RobotTask::_feedback [protected] |
Definition at line 64 of file RobotTask.h.
string robot_task::RobotTask::_name [protected] |
Definition at line 63 of file RobotTask.h.
ros::NodeHandle robot_task::RobotTask::_node [protected] |
Definition at line 61 of file RobotTask.h.
RESULT robot_task::RobotTask::_result [protected] |
Definition at line 65 of file RobotTask.h.
Server robot_task::RobotTask::_server [protected] |
Definition at line 62 of file RobotTask.h.
const int32_t robot_task::RobotTask::FAIL = 1 [static] |
Definition at line 44 of file RobotTask.h.
std::map<boost::thread::id,GOAL> robot_task::RobotTask::goalsByThread [protected] |
Definition at line 141 of file RobotTask.h.
const int32_t robot_task::RobotTask::PLAN = -1 [static] |
Definition at line 46 of file RobotTask.h.
const int32_t robot_task::RobotTask::SUCCESS = 0 [static] |
Definition at line 45 of file RobotTask.h.