00001 00025 #ifndef _DENSO_TASK_H_ 00026 #define _DENSO_TASK_H_ 00027 00028 #include "denso_robot_core/denso_base.h" 00029 #include "denso_robot_core/denso_variable.h" 00030 00031 #define XML_TASK_NAME "Task" 00032 00033 namespace denso_robot_core { 00034 00035 class DensoTask : public DensoBase 00036 { 00037 public: 00038 DensoTask(DensoBase* parent, 00039 Service_Vec& service, Handle_Vec& handle, 00040 const std::string& name, const int* mode); 00041 00042 virtual ~DensoTask(); 00043 00044 HRESULT InitializeBCAP(XMLElement *xmlElem); 00045 00046 HRESULT StartService(ros::NodeHandle& node); 00047 HRESULT StopService(); 00048 00049 bool Update(); 00050 00051 HRESULT get_Variable(const std::string& name, DensoVariable_Ptr* var); 00052 00053 HRESULT AddVariable(const std::string& name); 00054 00055 private: 00056 HRESULT AddVariable(XMLElement* xmlElem); 00057 00058 private: 00059 DensoVariable_Vec m_vecVar; 00060 }; 00061 00062 typedef boost::shared_ptr<DensoTask> DensoTask_Ptr; 00063 typedef std::vector<DensoTask_Ptr> DensoTask_Vec; 00064 00065 } 00066 00067 #endif