25 #ifndef _DENSO_BASE_H_ 26 #define _DENSO_BASE_H_ 29 #include "bcap_core/bcap_funcid.h" 33 #include <std_msgs/Int32.h> 34 #include <std_msgs/Float32.h> 35 #include <std_msgs/Float64.h> 36 #include <std_msgs/String.h> 37 #include <std_msgs/Bool.h> 38 #include <std_msgs/Float32MultiArray.h> 39 #include <std_msgs/Float64MultiArray.h> 43 #include "denso_robot_core/Joints.h" 44 #include "denso_robot_core/ExJoints.h" 45 #include "denso_robot_core/PoseData.h" 46 #include "denso_robot_core/UserIO.h" 53 #include "denso_robot_core/MoveStringAction.h" 54 #include "denso_robot_core/MoveValueAction.h" 55 #include "denso_robot_core/DriveStringAction.h" 56 #include "denso_robot_core/DriveValueAction.h" 61 #define MESSAGE_QUEUE (1) 62 #define BCAP_VAR_DEFAULT_DURATION (1000) 81 static std::string ConvertBSTRToString(
const BSTR bstr);
82 static BSTR ConvertStringToBSTR(
const std::string& str);
87 m_name(name), m_mode(mode), m_serving(false)
93 Service_Vec& service, Handle_Vec& handle,
94 const std::string& name,
const int* mode)
96 m_name(name), m_mode(mode), m_serving(false)
98 m_vecService = service;
129 const std::string&
Name()
const 134 std::string RosName()
const;
138 const std::string& name,
148 Handle_Vec& vecHandle);
virtual HRESULT InitializeBCAP()
std::vector< uint32_t > Handle_Vec
virtual HRESULT TerminateBCAP()
std::vector< BCAPService_Ptr > Service_Vec
std::vector< std::string > Name_Vec
boost::shared_ptr< DensoBase > DensoBase_Ptr
std::vector< DensoBase_Ptr > DensoBase_Vec
DensoBase(const std::string &name, const int *mode)
virtual HRESULT StopService()
#define BCAP_VAR_DEFAULT_DURATION
const std::string & Name() const
DensoBase(DensoBase *parent, Service_Vec &service, Handle_Vec &handle, const std::string &name, const int *mode)