denso_variable.h
Go to the documentation of this file.
1 
25 #ifndef DENSO_VARIABLE_H
26 #define DENSO_VARIABLE_H
27 
29 
30 namespace denso_robot_core
31 {
32 class DensoVariable : public DensoBase
33 {
34 public:
35  static constexpr const char* NAME_READ = "_Read";
36  static constexpr const char* NAME_WRITE = "_Write";
37  static constexpr const char* NAME_ID = "_ID";
38 
39  static constexpr const char* XML_VARIABLE_NAME = "Variable";
40 
41  static constexpr const char* XML_ATTR_VARTYPE = "vt";
42  static constexpr const char* XML_ATTR_READ = "read";
43  static constexpr const char* XML_ATTR_WRITE = "write";
44  static constexpr const char* XML_ATTR_ID = "id";
45  static constexpr const char* XML_ATTR_DURATION = "duration";
46 
47  DensoVariable(DensoBase* parent, Service_Vec& service, Handle_Vec& handle, const std::string& name, const int* mode,
48  int16_t vt, bool Read, bool Write, bool ID, int Duration);
49 
50  virtual ~DensoVariable();
51 
54 
55  bool Update();
56 
58  HRESULT ExecPutValue(const VARIANT_Ptr& value);
59  HRESULT ExecPutID(const int id);
60 
61 private:
62  // Callback functions
63  void Callback_I32(const Int32::ConstPtr& msg);
64  void Callback_F32(const Float32::ConstPtr& msg);
65  void Callback_F64(const Float64::ConstPtr& msg);
66  void Callback_String(const String::ConstPtr& msg);
67  void Callback_Bool(const Bool::ConstPtr& msg);
68  void Callback_F32Array(const Float32MultiArray::ConstPtr& msg);
69  void Callback_F64Array(const Float64MultiArray::ConstPtr& msg);
70  void Callback_ID(const Int32::ConstPtr& msg);
71 
72 private:
74  bool m_bRead;
75  bool m_bWrite;
76  bool m_bID;
82 };
83 
85 typedef std::vector<DensoVariable_Ptr> DensoVariable_Vec;
86 
87 } // namespace denso_robot_core
88 
89 #endif // DENSO_VARIABLE_H
short int16_t
static constexpr const char * XML_ATTR_VARTYPE
static constexpr const char * XML_ATTR_ID
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
static constexpr const char * XML_ATTR_WRITE
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
static constexpr const char * NAME_ID
void Callback_String(const String::ConstPtr &msg)
static constexpr const char * XML_ATTR_DURATION
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)
static constexpr const char * NAME_READ
static constexpr const char * XML_VARIABLE_NAME
static constexpr const char * NAME_WRITE
void Callback_F64Array(const Float64MultiArray::ConstPtr &msg)
static constexpr const char * XML_ATTR_READ
void Callback_Bool(const Bool::ConstPtr &msg)
void Callback_F64(const Float64::ConstPtr &msg)


denso_robot_core
Author(s): DENSO WAVE INCORPORATED
autogenerated on Sat Feb 18 2023 04:06:02