denso_controller.h
Go to the documentation of this file.
1 
25 #ifndef _DENSO_CONTROLLER_H_
26 #define _DENSO_CONTROLLER_H_
27 
32 
33 #define XML_CTRL_NAME "Controller"
34 
35 namespace denso_robot_core {
36 
37 class DensoController : public DensoBase
38 {
39 public:
40  DensoController(const std::string& name, const int* mode);
41  virtual ~DensoController();
42 
43  virtual HRESULT InitializeBCAP(
44  const std::string& filename);
45 
46  virtual HRESULT StartService(ros::NodeHandle& node);
47  virtual HRESULT StopService();
48 
49  virtual bool Update();
50 
51  HRESULT get_Robot(int index, DensoRobot_Ptr* robot);
52  HRESULT get_Task(const std::string& name, DensoTask_Ptr* task);
53  HRESULT get_Variable(const std::string& name, DensoVariable_Ptr* var);
54 
55  HRESULT AddVariable(const std::string& name);
56 
57 protected:
58  virtual HRESULT AddController() = 0;
59  virtual HRESULT AddRobot(XMLElement *xmlElem) = 0;
60  virtual HRESULT AddTask(XMLElement *xmlElem);
61  virtual HRESULT AddVariable(XMLElement* xmlElem);
62 
63 protected:
67 };
68 
70 
71 }
72 
73 #endif
virtual HRESULT AddRobot(XMLElement *xmlElem)=0
filename
virtual HRESULT InitializeBCAP()
Definition: denso_base.h:107
std::vector< DensoRobot_Ptr > DensoRobot_Vec
Definition: denso_robot.h:81
virtual HRESULT StartService(ros::NodeHandle &node)
std::vector< DensoTask_Ptr > DensoTask_Vec
Definition: denso_task.h:63
HRESULT get_Robot(int index, DensoRobot_Ptr *robot)
int32_t HRESULT
std::vector< DensoVariable_Ptr > DensoVariable_Vec
virtual HRESULT AddTask(XMLElement *xmlElem)
HRESULT get_Task(const std::string &name, DensoTask_Ptr *task)
virtual HRESULT AddController()=0
HRESULT get_Variable(const std::string &name, DensoVariable_Ptr *var)
boost::shared_ptr< DensoController > DensoController_Ptr
HRESULT AddVariable(const std::string &name)
DensoController(const std::string &name, const int *mode)


denso_robot_core
Author(s): DENSO WAVE INCORPORATED
autogenerated on Mon Jun 10 2019 13:12:27