25 #ifndef _DENSO_VARIABLE_H_ 26 #define _DENSO_VARIABLE_H_ 30 #define XML_VARIABLE_NAME "Variable" 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" 45 const std::string& name,
const int* mode,
ros::Publisher m_pubValue
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
HRESULT ExecPutID(const int id)
HRESULT StartService(ros::NodeHandle &node)
std::vector< BCAPService_Ptr > Service_Vec
void Callback_I32(const Int32::ConstPtr &msg)
boost::shared_ptr< DensoVariable > DensoVariable_Ptr
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)
ros::Subscriber m_subValue
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)
void Callback_F64Array(const Float64MultiArray::ConstPtr &msg)
void Callback_Bool(const Bool::ConstPtr &msg)
void Callback_F64(const Float64::ConstPtr &msg)