denso_controller.h
Go to the documentation of this file.
1 
25 #ifndef DENSO_CONTROLLER_H
26 #define DENSO_CONTROLLER_H
27 
32 
33 namespace denso_robot_core
34 {
35 class DensoController : public DensoBase
36 {
37 public:
38  static constexpr int BCAP_CONTROLLER_CONNECT_ARGS = 4;
39  static constexpr int BCAP_CONTROLLER_EXECUTE_ARGS = 3;
40 
41  static constexpr const char* XML_CTRL_NAME = "Controller";
42 
43  virtual ~DensoController();
44 
45  virtual HRESULT InitializeBCAP(const std::string& filename);
46 
47  virtual HRESULT StartService(ros::NodeHandle& node);
48  virtual HRESULT StopService();
49 
50  virtual bool Update();
51 
52  HRESULT get_Robot(int index, DensoRobot_Ptr* robot);
53  HRESULT get_Task(const std::string& name, DensoTask_Ptr* task);
54  HRESULT get_Variable(const std::string& name, DensoVariable_Ptr* var);
55 
56  HRESULT AddVariable(const std::string& name);
57  virtual HRESULT ExecClearError();
58  virtual HRESULT ExecManualReset() = 0;
59  virtual HRESULT ExecResetStoState() = 0;
60  virtual HRESULT ExecGetCurErrorCount(int& count);
61  virtual HRESULT ExecGetCurErrorInfo(int error_index, HRESULT& error_code, std::string& error_message);
62  virtual HRESULT ExecGetErrorDescription(HRESULT error_code, std::string& error_description);
63 
65  {
66  return m_duration;
67  }
68  std::tuple<int, int, int> get_SoftwareVersion() const
69  {
70  return m_software_version;
71  }
72 
73 protected:
74  DensoController(const std::string& name, const int* mode, const ros::Duration dt);
75  virtual HRESULT AddController() = 0;
76  virtual HRESULT AddRobot(XMLElement* xmlElem) = 0;
77  virtual HRESULT AddTask(XMLElement* xmlElem);
78  virtual HRESULT AddVariable(XMLElement* xmlElem);
79 
80 protected:
85 
86 private:
87  std::tuple<int, int, int> m_software_version;
89 };
90 
92 
93 } // namespace denso_robot_core
94 
95 #endif // DENSO_CONTROLLER_H
virtual HRESULT AddRobot(XMLElement *xmlElem)=0
virtual HRESULT InitializeBCAP()
Definition: denso_base.h:104
std::vector< DensoRobot_Ptr > DensoRobot_Vec
Definition: denso_robot.h:222
ros::Duration get_Duration() const
virtual HRESULT StartService(ros::NodeHandle &node)
std::vector< DensoTask_Ptr > DensoTask_Vec
Definition: denso_task.h:61
std::tuple< int, int, int > m_software_version
DensoController(const std::string &name, const int *mode, const ros::Duration dt)
HRESULT get_Robot(int index, DensoRobot_Ptr *robot)
int32_t HRESULT
std::vector< DensoVariable_Ptr > DensoVariable_Vec
std::tuple< int, int, int > get_SoftwareVersion() const
virtual HRESULT AddTask(XMLElement *xmlElem)
virtual HRESULT ExecGetCurErrorCount(int &count)
HRESULT get_Task(const std::string &name, DensoTask_Ptr *task)
virtual HRESULT AddController()=0
virtual HRESULT ExecResetStoState()=0
virtual HRESULT ExecGetErrorDescription(HRESULT error_code, std::string &error_description)
HRESULT get_Variable(const std::string &name, DensoVariable_Ptr *var)
virtual HRESULT ExecGetCurErrorInfo(int error_index, HRESULT &error_code, std::string &error_message)
static constexpr int BCAP_CONTROLLER_CONNECT_ARGS
boost::shared_ptr< DensoController > DensoController_Ptr
virtual HRESULT ExecManualReset()=0
static constexpr int BCAP_CONTROLLER_EXECUTE_ARGS
HRESULT AddVariable(const std::string &name)
static constexpr const char * XML_CTRL_NAME


denso_robot_core
Author(s): DENSO WAVE INCORPORATED
autogenerated on Sat Feb 18 2023 04:06:02