25 #ifndef DENSO_VARIABLE_H 26 #define DENSO_VARIABLE_H 37 static constexpr
const char*
NAME_ID =
"_ID";
48 int16_t vt,
bool Read,
bool Write,
bool ID,
int Duration);
89 #endif // DENSO_VARIABLE_H
static constexpr const char * XML_ATTR_VARTYPE
static constexpr const char * XML_ATTR_ID
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
static constexpr const char * XML_ATTR_WRITE
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
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)
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)
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)