Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
denso_robot_core::DensoController Class Referenceabstract

#include <denso_controller.h>

Inheritance diagram for denso_robot_core::DensoController:
Inheritance graph
[legend]

Public Member Functions

HRESULT AddVariable (const std::string &name)
 
 DensoController (const std::string &name, const int *mode)
 
HRESULT get_Robot (int index, DensoRobot_Ptr *robot)
 
HRESULT get_Task (const std::string &name, DensoTask_Ptr *task)
 
HRESULT get_Variable (const std::string &name, DensoVariable_Ptr *var)
 
virtual HRESULT InitializeBCAP (const std::string &filename)
 
virtual HRESULT StartService (ros::NodeHandle &node)
 
virtual HRESULT StopService ()
 
virtual bool Update ()
 
virtual ~DensoController ()
 
- Public Member Functions inherited from denso_robot_core::DensoBase
 DensoBase (const std::string &name, const int *mode)
 
 DensoBase (DensoBase *parent, Service_Vec &service, Handle_Vec &handle, const std::string &name, const int *mode)
 
virtual HRESULT InitializeBCAP ()
 
const std::string & Name () const
 
std::string RosName () const
 
virtual HRESULT TerminateBCAP ()
 
virtual ~DensoBase ()
 

Protected Member Functions

virtual HRESULT AddController ()=0
 
virtual HRESULT AddRobot (XMLElement *xmlElem)=0
 
virtual HRESULT AddTask (XMLElement *xmlElem)
 
virtual HRESULT AddVariable (XMLElement *xmlElem)
 
- Protected Member Functions inherited from denso_robot_core::DensoBase
HRESULT AddObject (int32_t get_id, const std::string &name, Handle_Vec &vecHandle)
 
HRESULT AddVariable (int32_t get_id, const std::string &name, std::vector< boost::shared_ptr< class DensoVariable > > &vecVar, int16_t vt=VT_EMPTY, bool bRead=false, bool bWrite=false, bool bID=false, int iDuration=BCAP_VAR_DEFAULT_DURATION)
 
HRESULT AddVariable (int32_t get_id, const XMLElement *xmlVar, std::vector< boost::shared_ptr< class DensoVariable > > &vecVar)
 
HRESULT get_Object (const std::vector< boost::shared_ptr< DensoBase > > &vecBase, int index, boost::shared_ptr< DensoBase > *obj)
 
HRESULT get_Object (const std::vector< boost::shared_ptr< DensoBase > > &vecBase, const std::string &name, boost::shared_ptr< DensoBase > *obj)
 
HRESULT GetObjectNames (int32_t func_id, Name_Vec &vecName)
 

Protected Attributes

DensoRobot_Vec m_vecRobot
 
DensoTask_Vec m_vecTask
 
DensoVariable_Vec m_vecVar
 
- Protected Attributes inherited from denso_robot_core::DensoBase
const int * m_mode
 
boost::mutex m_mtxSrv
 
std::string m_name
 
DensoBasem_parent
 
bool m_serving
 
Handle_Vec m_vecHandle
 
Service_Vec m_vecService
 

Additional Inherited Members

- Public Types inherited from denso_robot_core::DensoBase
enum  { SRV_MIN = 0, SRV_ACT = SRV_MIN, SRV_WATCH, SRV_MAX = SRV_WATCH }
 
- Static Public Member Functions inherited from denso_robot_core::DensoBase
static std::string ConvertBSTRToString (const BSTR bstr)
 
static BSTR ConvertStringToBSTR (const std::string &str)
 

Detailed Description

Definition at line 37 of file denso_controller.h.

Constructor & Destructor Documentation

denso_robot_core::DensoController::DensoController ( const std::string &  name,
const int *  mode 
)

Definition at line 29 of file denso_controller.cpp.

denso_robot_core::DensoController::~DensoController ( )
virtual

Definition at line 47 of file denso_controller.cpp.

Member Function Documentation

virtual HRESULT denso_robot_core::DensoController::AddController ( )
protectedpure virtual
virtual HRESULT denso_robot_core::DensoController::AddRobot ( XMLElement xmlElem)
protectedpure virtual
HRESULT denso_robot_core::DensoController::AddTask ( XMLElement xmlElem)
protectedvirtual

Definition at line 240 of file denso_controller.cpp.

HRESULT denso_robot_core::DensoController::AddVariable ( const std::string &  name)

Definition at line 267 of file denso_controller.cpp.

HRESULT denso_robot_core::DensoController::AddVariable ( XMLElement xmlElem)
protectedvirtual

Definition at line 273 of file denso_controller.cpp.

HRESULT denso_robot_core::DensoController::get_Robot ( int  index,
DensoRobot_Ptr robot 
)

Definition at line 186 of file denso_controller.cpp.

HRESULT denso_robot_core::DensoController::get_Task ( const std::string &  name,
DensoTask_Ptr task 
)

Definition at line 204 of file denso_controller.cpp.

HRESULT denso_robot_core::DensoController::get_Variable ( const std::string &  name,
DensoVariable_Ptr var 
)

Definition at line 222 of file denso_controller.cpp.

HRESULT denso_robot_core::DensoController::InitializeBCAP ( const std::string &  filename)
virtual

Definition at line 52 of file denso_controller.cpp.

HRESULT denso_robot_core::DensoController::StartService ( ros::NodeHandle node)
virtual

Implements denso_robot_core::DensoBase.

Definition at line 90 of file denso_controller.cpp.

HRESULT denso_robot_core::DensoController::StopService ( )
virtual

Reimplemented from denso_robot_core::DensoBase.

Definition at line 121 of file denso_controller.cpp.

bool denso_robot_core::DensoController::Update ( )
virtual

Reimplemented from denso_robot_core::DensoBase.

Definition at line 154 of file denso_controller.cpp.

Member Data Documentation

DensoRobot_Vec denso_robot_core::DensoController::m_vecRobot
protected

Definition at line 64 of file denso_controller.h.

DensoTask_Vec denso_robot_core::DensoController::m_vecTask
protected

Definition at line 65 of file denso_controller.h.

DensoVariable_Vec denso_robot_core::DensoController::m_vecVar
protected

Definition at line 66 of file denso_controller.h.


The documentation for this class was generated from the following files:


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