denso_controller.h
Go to the documentation of this file.
00001 
00025 #ifndef _DENSO_CONTROLLER_H_
00026 #define _DENSO_CONTROLLER_H_
00027 
00028 #include "denso_robot_core/denso_base.h"
00029 #include "denso_robot_core/denso_robot.h"
00030 #include "denso_robot_core/denso_task.h"
00031 #include "denso_robot_core/denso_variable.h"
00032 
00033 #define XML_CTRL_NAME "Controller"
00034 
00035 namespace denso_robot_core {
00036 
00037 class DensoController : public DensoBase
00038 {
00039 public:
00040   DensoController(const std::string& name, const int* mode);
00041   virtual ~DensoController();
00042 
00043   virtual HRESULT InitializeBCAP(
00044       const std::string& filename);
00045 
00046   virtual HRESULT StartService(ros::NodeHandle& node);
00047   virtual HRESULT StopService();
00048 
00049   virtual bool Update();
00050 
00051   HRESULT get_Robot(int index, DensoRobot_Ptr* robot);
00052   HRESULT get_Task(const std::string& name, DensoTask_Ptr* task);
00053   HRESULT get_Variable(const std::string& name, DensoVariable_Ptr* var);
00054 
00055   HRESULT AddVariable(const std::string& name);
00056 
00057 protected:
00058   virtual HRESULT AddController() = 0;
00059   virtual HRESULT AddRobot(XMLElement *xmlElem) = 0;
00060   virtual HRESULT AddTask(XMLElement *xmlElem);
00061   virtual HRESULT AddVariable(XMLElement* xmlElem);
00062 
00063 protected:
00064   DensoRobot_Vec    m_vecRobot;
00065   DensoTask_Vec     m_vecTask;
00066   DensoVariable_Vec m_vecVar;
00067 };
00068 
00069 typedef boost::shared_ptr<DensoController> DensoController_Ptr;
00070 
00071 }
00072 
00073 #endif


denso_robot_core
Author(s): DENSO WAVE INCORPORATED
autogenerated on Thu Jun 6 2019 21:00:11