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

#include <denso_robot.h>

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

Public Member Functions

HRESULT AddVariable (const std::string &name)
 
void ChangeArmGroup (int number)
 
 DensoRobot (DensoBase *parent, Service_Vec &service, Handle_Vec &handle, const std::string &name, const int *mode)
 
virtual HRESULT ExecGiveArm ()=0
 
virtual HRESULT ExecTakeArm ()=0
 
HRESULT get_Variable (const std::string &name, DensoVariable_Ptr *var)
 
virtual HRESULT InitializeBCAP (XMLElement *xmlElem)
 
virtual HRESULT StartService (ros::NodeHandle &node)
 
virtual HRESULT StopService ()
 
virtual bool Update ()
 
virtual ~DensoRobot ()
 
- 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 AddVariable (XMLElement *xmlElem)
 
void Callback_ArmGroup (const Int32::ConstPtr &msg)
 
HRESULT CreateExJoints (const ExJoints &exjoints, VARIANT &vnt)
 
HRESULT CreatePoseData (const PoseData &pose, VARIANT &vnt)
 
- 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

int32_t m_ArmGroup
 
ros::Subscriber m_subArmGroup
 
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 35 of file denso_robot.h.

Constructor & Destructor Documentation

denso_robot_core::DensoRobot::DensoRobot ( DensoBase parent,
Service_Vec service,
Handle_Vec handle,
const std::string &  name,
const int *  mode 
)

Definition at line 31 of file denso_robot.cpp.

denso_robot_core::DensoRobot::~DensoRobot ( )
virtual

Definition at line 40 of file denso_robot.cpp.

Member Function Documentation

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

Definition at line 136 of file denso_robot.cpp.

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

Definition at line 142 of file denso_robot.cpp.

void denso_robot_core::DensoRobot::Callback_ArmGroup ( const Int32::ConstPtr &  msg)
protected

Definition at line 113 of file denso_robot.cpp.

void denso_robot_core::DensoRobot::ChangeArmGroup ( int  number)

Definition at line 108 of file denso_robot.cpp.

HRESULT denso_robot_core::DensoRobot::CreateExJoints ( const ExJoints &  exjoints,
VARIANT vnt 
)
protected

Definition at line 201 of file denso_robot.cpp.

HRESULT denso_robot_core::DensoRobot::CreatePoseData ( const PoseData &  pose,
VARIANT vnt 
)
protected

Definition at line 159 of file denso_robot.cpp.

virtual HRESULT denso_robot_core::DensoRobot::ExecGiveArm ( )
pure virtual
virtual HRESULT denso_robot_core::DensoRobot::ExecTakeArm ( )
pure virtual
HRESULT denso_robot_core::DensoRobot::get_Variable ( const std::string &  name,
DensoVariable_Ptr var 
)

Definition at line 118 of file denso_robot.cpp.

HRESULT denso_robot_core::DensoRobot::InitializeBCAP ( XMLElement xmlElem)
virtual

Definition at line 45 of file denso_robot.cpp.

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

Implements denso_robot_core::DensoBase.

Reimplemented in denso_robot_core::DensoRobotRC8.

Definition at line 50 of file denso_robot.cpp.

HRESULT denso_robot_core::DensoRobot::StopService ( )
virtual

Reimplemented from denso_robot_core::DensoBase.

Reimplemented in denso_robot_core::DensoRobotRC8.

Definition at line 73 of file denso_robot.cpp.

bool denso_robot_core::DensoRobot::Update ( )
virtual

Reimplemented from denso_robot_core::DensoBase.

Reimplemented in denso_robot_core::DensoRobotRC8.

Definition at line 92 of file denso_robot.cpp.

Member Data Documentation

int32_t denso_robot_core::DensoRobot::m_ArmGroup
protected

Definition at line 76 of file denso_robot.h.

ros::Subscriber denso_robot_core::DensoRobot::m_subArmGroup
protected

Definition at line 77 of file denso_robot.h.

DensoVariable_Vec denso_robot_core::DensoRobot::m_vecVar
protected

Definition at line 74 of file denso_robot.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