denso_variable.h
Go to the documentation of this file.
1 
25 #ifndef _DENSO_VARIABLE_H_
26 #define _DENSO_VARIABLE_H_
27 
29 
30 #define XML_VARIABLE_NAME "Variable"
31 
32 #define XML_ATTR_VARTYPE "vt"
33 #define XML_ATTR_READ "read"
34 #define XML_ATTR_WRITE "write"
35 #define XML_ATTR_ID "id"
36 #define XML_ATTR_DURATION "duration"
37 
38 namespace denso_robot_core {
39 
40 class DensoVariable : public DensoBase
41 {
42 public:
43  DensoVariable(DensoBase* parent,
44  Service_Vec& service, Handle_Vec& handle,
45  const std::string& name, const int* mode,
46  int16_t vt, bool Read, bool Write, bool ID, int Duration);
47 
48  virtual ~DensoVariable();
49 
52 
53  bool Update();
54 
56  HRESULT ExecPutValue(const VARIANT_Ptr& value);
57  HRESULT ExecPutID(const int id);
58 
59 private:
60  // Callback functions
61  void Callback_I32(const Int32::ConstPtr& msg);
62  void Callback_F32(const Float32::ConstPtr& msg);
63  void Callback_F64(const Float64::ConstPtr& msg);
64  void Callback_String(const String::ConstPtr& msg);
65  void Callback_Bool(const Bool::ConstPtr& msg);
66  void Callback_F32Array(const Float32MultiArray::ConstPtr& msg);
67  void Callback_F64Array(const Float64MultiArray::ConstPtr& msg);
68  void Callback_ID(const Int32::ConstPtr& msg);
69 
70 private:
72  bool m_bRead;
73  bool m_bWrite;
74  bool m_bID;
80 };
81 
83 typedef std::vector<DensoVariable_Ptr> DensoVariable_Vec;
84 
85 }
86 
87 #endif
short int16_t
Write
HRESULT ExecPutValue(const VARIANT_Ptr &value)
void Callback_F32Array(const Float32MultiArray::ConstPtr &msg)
void Callback_ID(const Int32::ConstPtr &msg)
std::vector< uint32_t > Handle_Vec
Definition: denso_base.h:67
HRESULT ExecPutID(const int id)
HRESULT StartService(ros::NodeHandle &node)
std::vector< BCAPService_Ptr > Service_Vec
Definition: denso_base.h:68
void Callback_I32(const Int32::ConstPtr &msg)
boost::shared_ptr< DensoVariable > DensoVariable_Ptr
int32_t HRESULT
void Callback_String(const String::ConstPtr &msg)
std::vector< DensoVariable_Ptr > DensoVariable_Vec
boost::interprocess::unique_ptr< VARIANT, variant_deleter > VARIANT_Ptr
HRESULT ExecGetValue(VARIANT_Ptr &value)
void Callback_F32(const Float32::ConstPtr &msg)
DensoVariable(DensoBase *parent, Service_Vec &service, Handle_Vec &handle, const std::string &name, const int *mode, int16_t vt, bool Read, bool Write, bool ID, int Duration)
Read
void Callback_F64Array(const Float64MultiArray::ConstPtr &msg)
void Callback_Bool(const Bool::ConstPtr &msg)
void Callback_F64(const Float64::ConstPtr &msg)


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