25 #ifndef _DENSO_TASK_H_ 26 #define _DENSO_TASK_H_ 31 #define XML_TASK_NAME "Task" 40 const std::string& name,
const int* mode);
HRESULT get_Variable(const std::string &name, DensoVariable_Ptr *var)
DensoTask(DensoBase *parent, Service_Vec &service, Handle_Vec &handle, const std::string &name, const int *mode)
virtual HRESULT InitializeBCAP()
DensoVariable_Vec m_vecVar
std::vector< DensoTask_Ptr > DensoTask_Vec
std::vector< uint32_t > Handle_Vec
std::vector< BCAPService_Ptr > Service_Vec
std::vector< DensoVariable_Ptr > DensoVariable_Vec
HRESULT AddVariable(const std::string &name)
boost::shared_ptr< DensoTask > DensoTask_Ptr
HRESULT StartService(ros::NodeHandle &node)