00001 00002 #ifndef TASKMANAGER_H 00003 #define TASKMANAGER_H 00004 00005 #include <ros/ros.h> 00006 #include <vector> 00007 #include <string> 00008 00009 #include "bwi_msgs/ScavStatus.h" 00010 #include "ScavTask.h" 00011 00012 enum TaskStatus { ONGOING, FINISHED, TODO }; 00013 00014 struct TaskWithStatus { 00015 ScavTask *task; 00016 TaskStatus status; 00017 std::string certificate; 00018 00019 TaskWithStatus() : task(NULL), status(TODO) {} 00020 00021 TaskWithStatus(ScavTask *scav_task, TaskStatus scav_status) : 00022 task(scav_task), status(scav_status) {} 00023 }; 00024 00025 class TaskManager { 00026 00027 public: 00028 00029 TaskManager() {} 00030 TaskManager(ros::NodeHandle *); 00031 00032 ros::NodeHandle *nh; 00033 00034 ros::ServiceClient gui_client; 00035 00036 std::vector<TaskWithStatus> tasks; 00037 00038 void addTask(TaskWithStatus* task); 00039 00040 void executeNextTask(int timeout, TaskWithStatus *task); 00041 00042 void updateStatusGui(); 00043 00044 void publishStatus(); 00045 00046 bool allFinished(); 00047 00048 TaskWithStatus *selectNextTask(); 00049 00050 bool paused; 00051 private: 00052 00053 ros::Publisher pub; 00054 bwi_msgs::ScavStatus msg; 00055 00056 00057 00058 }; 00059 00060 00061 #endif