25 #ifndef _DENSO_ROBOT_H_ 26 #define _DENSO_ROBOT_H_ 31 #define XML_ROBOT_NAME "Robot" 40 const std::string& name,
const int* mode);
70 const ExJoints &exjoints,
void ChangeArmGroup(int number)
virtual HRESULT InitializeBCAP()
std::vector< DensoRobot_Ptr > DensoRobot_Vec
HRESULT AddVariable(const std::string &name)
DensoRobot(DensoBase *parent, Service_Vec &service, Handle_Vec &handle, const std::string &name, const int *mode)
void Callback_ArmGroup(const Int32::ConstPtr &msg)
ros::Subscriber m_subArmGroup
std::vector< uint32_t > Handle_Vec
virtual HRESULT ExecGiveArm()=0
std::vector< BCAPService_Ptr > Service_Vec
boost::shared_ptr< DensoRobot > DensoRobot_Ptr
std::vector< DensoVariable_Ptr > DensoVariable_Vec
DensoVariable_Vec m_vecVar
HRESULT CreateExJoints(const ExJoints &exjoints, VARIANT &vnt)
HRESULT get_Variable(const std::string &name, DensoVariable_Ptr *var)
virtual HRESULT StartService(ros::NodeHandle &node)
virtual HRESULT StopService()
virtual HRESULT ExecTakeArm()=0
HRESULT CreatePoseData(const PoseData &pose, VARIANT &vnt)