denso_robot.h
Go to the documentation of this file.
1 
25 #ifndef _DENSO_ROBOT_H_
26 #define _DENSO_ROBOT_H_
27 
30 
31 #define XML_ROBOT_NAME "Robot"
32 
33 namespace denso_robot_core {
34 
35 class DensoRobot : public DensoBase
36 {
37 public:
38  DensoRobot(DensoBase* parent,
39  Service_Vec& service, Handle_Vec& handle,
40  const std::string& name, const int* mode);
41 
42  virtual ~DensoRobot();
43 
44  virtual HRESULT InitializeBCAP(XMLElement *xmlElem);
45 
46  virtual HRESULT StartService(ros::NodeHandle& node);
47  virtual HRESULT StopService();
48 
49  virtual bool Update();
50 
51  HRESULT get_Variable(const std::string& name, DensoVariable_Ptr* var);
52 
53  HRESULT AddVariable(const std::string& name);
54 
55  virtual HRESULT ExecTakeArm() = 0;
56  virtual HRESULT ExecGiveArm() = 0;
57 
58  void ChangeArmGroup(int number);
59 
60 protected:
61  void Callback_ArmGroup(const Int32::ConstPtr& msg);
62 
63  virtual HRESULT AddVariable(XMLElement* xmlElem);
64 
66  const PoseData &pose,
67  VARIANT &vnt);
68 
70  const ExJoints &exjoints,
71  VARIANT &vnt);
72 
73 protected:
75 
78 };
79 
81 typedef std::vector<DensoRobot_Ptr> DensoRobot_Vec;
82 
83 }
84 
85 #endif
void ChangeArmGroup(int number)
virtual HRESULT InitializeBCAP()
Definition: denso_base.h:107
std::vector< DensoRobot_Ptr > DensoRobot_Vec
Definition: denso_robot.h:81
HRESULT AddVariable(const std::string &name)
DensoRobot(DensoBase *parent, Service_Vec &service, Handle_Vec &handle, const std::string &name, const int *mode)
Definition: denso_robot.cpp:31
void Callback_ArmGroup(const Int32::ConstPtr &msg)
ros::Subscriber m_subArmGroup
Definition: denso_robot.h:77
std::vector< uint32_t > Handle_Vec
Definition: denso_base.h:67
virtual HRESULT ExecGiveArm()=0
std::vector< BCAPService_Ptr > Service_Vec
Definition: denso_base.h:68
int32_t HRESULT
boost::shared_ptr< DensoRobot > DensoRobot_Ptr
Definition: denso_robot.h:80
std::vector< DensoVariable_Ptr > DensoVariable_Vec
DensoVariable_Vec m_vecVar
Definition: denso_robot.h:74
HRESULT CreateExJoints(const ExJoints &exjoints, VARIANT &vnt)
HRESULT get_Variable(const std::string &name, DensoVariable_Ptr *var)
int int32_t
virtual HRESULT StartService(ros::NodeHandle &node)
Definition: denso_robot.cpp:50
virtual HRESULT StopService()
Definition: denso_robot.cpp:73
virtual HRESULT ExecTakeArm()=0
HRESULT CreatePoseData(const PoseData &pose, VARIANT &vnt)


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