25 #ifndef DENSO_CONTROLLER_H 26 #define DENSO_CONTROLLER_H 95 #endif // DENSO_CONTROLLER_H
virtual HRESULT AddRobot(XMLElement *xmlElem)=0
virtual HRESULT InitializeBCAP()
std::vector< DensoRobot_Ptr > DensoRobot_Vec
ros::Duration get_Duration() const
virtual HRESULT StartService(ros::NodeHandle &node)
std::vector< DensoTask_Ptr > DensoTask_Vec
DensoRobot_Vec m_vecRobot
virtual HRESULT ExecClearError()
std::tuple< int, int, int > m_software_version
DensoVariable_Vec m_vecVar
DensoController(const std::string &name, const int *mode, const ros::Duration dt)
HRESULT get_Robot(int index, DensoRobot_Ptr *robot)
virtual HRESULT StopService()
HRESULT GetVariableVersion()
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 ~DensoController()
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