00001 00025 #ifndef _DENSO_VARIABLE_H_ 00026 #define _DENSO_VARIABLE_H_ 00027 00028 #include "denso_robot_core/denso_base.h" 00029 00030 #define XML_VARIABLE_NAME "Variable" 00031 00032 #define XML_ATTR_VARTYPE "vt" 00033 #define XML_ATTR_READ "read" 00034 #define XML_ATTR_WRITE "write" 00035 #define XML_ATTR_ID "id" 00036 #define XML_ATTR_DURATION "duration" 00037 00038 namespace denso_robot_core { 00039 00040 class DensoVariable : public DensoBase 00041 { 00042 public: 00043 DensoVariable(DensoBase* parent, 00044 Service_Vec& service, Handle_Vec& handle, 00045 const std::string& name, const int* mode, 00046 int16_t vt, bool Read, bool Write, bool ID, int Duration); 00047 00048 virtual ~DensoVariable(); 00049 00050 HRESULT StartService(ros::NodeHandle& node); 00051 HRESULT StopService(); 00052 00053 bool Update(); 00054 00055 HRESULT ExecGetValue(VARIANT_Ptr& value); 00056 HRESULT ExecPutValue(const VARIANT_Ptr& value); 00057 HRESULT ExecPutID(const int id); 00058 00059 private: 00060 // Callback functions 00061 void Callback_I32(const Int32::ConstPtr& msg); 00062 void Callback_F32(const Float32::ConstPtr& msg); 00063 void Callback_F64(const Float64::ConstPtr& msg); 00064 void Callback_String(const String::ConstPtr& msg); 00065 void Callback_Bool(const Bool::ConstPtr& msg); 00066 void Callback_F32Array(const Float32MultiArray::ConstPtr& msg); 00067 void Callback_F64Array(const Float64MultiArray::ConstPtr& msg); 00068 void Callback_ID(const Int32::ConstPtr& msg); 00069 00070 private: 00071 int16_t m_vt; 00072 bool m_bRead; 00073 bool m_bWrite; 00074 bool m_bID; 00075 ros::Duration m_Duration; 00076 ros::Time m_pubTimePrev; 00077 ros::Publisher m_pubValue; 00078 ros::Subscriber m_subValue; 00079 ros::Subscriber m_subID; 00080 }; 00081 00082 typedef boost::shared_ptr<DensoVariable> DensoVariable_Ptr; 00083 typedef std::vector<DensoVariable_Ptr> DensoVariable_Vec; 00084 00085 } 00086 00087 #endif