28 #include "bcap_core/bcap_funcid.h" 29 #include "bcap_core/bCAPClient/bcap_client.h" 30 #include "bcap_core/RACString/rac_string.h" 32 int main(
int argc,
char** argv)
61 : m_type(
""), m_addr(
""),
62 m_port(0), m_timeout(0), m_retry(0), m_wait(0),
63 m_fd(0), m_wdt(0), m_invoke(0)
122 std::stringstream ss1;
123 std::wstringstream ss2;
142 KeyHandle_Vec::iterator it;
224 unsigned int value = 0;
246 for(
int i = 0; i < req.vntArgs.size(); i++) {
250 req.vntArgs[i].vt, req.vntArgs[i].value.c_str(),
252 if(
FAILED(hr))
goto err_proc;
253 vntArgs.push_back(*vntTmp.get());
257 if(
FAILED(hr))
goto err_proc;
260 if(
FAILED(hr))
goto err_proc;
263 res.vntRet.vt = vntRet->vt;
264 res.vntRet.value = chRet;
274 res.vntRet.value =
"";
292 vntArgs.at(0).bstrVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal, vntArgs.at(3).bstrVal,
297 tmpKH.second = vntArgs.at(0).ulVal;
299 &vntArgs.at(0).ulVal);
304 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
311 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
318 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
325 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
332 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
339 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
345 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
350 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
355 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
360 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
365 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
370 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
375 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2),
410 vntArgs.at(0).ulVal, vntArgs.at(1));
419 vntArgs.at(0).ulVal, vntArgs.at(1));
425 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
431 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
436 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2),
464 vntArgs.at(0).ulVal, vntArgs.at(1));
473 vntArgs.at(0).ulVal, vntArgs.at(1));
476 tmpKH.second = vntArgs.at(0).ulVal;
478 &vntArgs.at(0).ulVal);
484 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
491 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
497 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
502 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
507 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2),
512 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal);
516 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal);
520 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal);
525 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
568 vntArgs.at(0).ulVal, vntArgs.at(1));
595 vntArgs.at(0).ulVal, vntArgs.at(1));
604 vntArgs.at(0).ulVal, vntArgs.at(1));
607 tmpKH.second = vntArgs.at(0).ulVal;
609 &vntArgs.at(0).ulVal);
615 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
621 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
626 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2),
631 vntArgs.at(0).ulVal, vntArgs.at(1).lVal, vntArgs.at(2).fltVal, vntArgs.at(3).fltVal);
635 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal);
639 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal);
643 vntArgs.at(0).ulVal, vntArgs.at(1).lVal, vntArgs.at(2).fltVal, vntArgs.at(3).bstrVal);
647 vntArgs.at(0).ulVal);
651 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal);
655 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal);
659 vntArgs.at(0).ulVal, vntArgs.at(1).lVal, vntArgs.at(2), vntArgs.at(3).bstrVal);
663 vntArgs.at(0).ulVal, vntArgs.at(1), vntArgs.at(2).fltVal, vntArgs.at(3), vntArgs.at(4).bstrVal);
667 vntArgs.at(0).ulVal, vntArgs.at(1).lVal, vntArgs.at(2).fltVal);
671 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal);
675 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal);
702 vntArgs.at(0).ulVal, vntArgs.at(1));
711 vntArgs.at(0).ulVal, vntArgs.at(1));
714 tmpKH.second = vntArgs.at(0).ulVal;
716 &vntArgs.at(0).ulVal);
722 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
728 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
733 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2),
738 vntArgs.at(0).ulVal, vntArgs.at(1).lVal, vntArgs.at(2).bstrVal);
742 vntArgs.at(0).ulVal, vntArgs.at(1).lVal, vntArgs.at(2).bstrVal);
746 vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal);
779 vntArgs.at(0).ulVal, vntArgs.at(1));
788 vntArgs.at(0).ulVal, vntArgs.at(1));
791 tmpKH.second = vntArgs.at(0).ulVal;
793 &vntArgs.at(0).ulVal);
808 vntArgs.at(0).ulVal, vntArgs.at(1));
835 vntArgs.at(0).ulVal, vntArgs.at(1));
844 vntArgs.at(0).ulVal, vntArgs.at(1));
853 tmpKH.second = vntArgs.at(0).ulVal;
855 &vntArgs.at(0).ulVal);
860 vntArgs.at(0).ulVal, vntArgs.at(1).lVal,
865 vntArgs.at(0).ulVal);
875 vntArgs.at(0).ulVal, vntArgs.at(1).lVal);
890 vntArgs.at(0).ulVal, vntArgs.at(1));
922 vntArgs.at(0).ulVal, vntArgs.at(1));
931 vntArgs.at(0).ulVal, vntArgs.at(1));
934 tmpKH.second = vntArgs.at(0).ulVal;
936 &vntArgs.at(0).ulVal);
940 vntArgs.at(0).ulVal, vntArgs.at(1));
944 vntArgs.at(0).ulVal);
987 tmpKH.second = vntArgs.at(0).ulVal;
989 &vntArgs.at(0).ulVal);
992 }
catch(std::out_of_range&) {
997 if(tmpKH.first > 0) {
998 tmpKH.second = vntRet->ulVal;
1001 else if(tmpKH.second > 0) {
1002 KeyHandle_Vec::iterator it;
1004 if((func_id == it->first)
1005 && (tmpKH.second == it->second))
HRESULT bCap_CommandPutID(int fd, uint32_t hCommand, VARIANT newVal)
#define ID_MESSAGE_GETSOURCE
HRESULT bCap_TaskGetVariable(int fd, uint32_t hTask, BSTR bstrName, BSTR bstrOption, uint32_t *hVariable)
HRESULT bCap_ControllerGetExtension(int fd, uint32_t hController, BSTR bstrName, BSTR bstrOption, uint32_t *hExtension)
HRESULT bCap_RobotHalt(int fd, uint32_t hRobot, BSTR bstrOption)
void SysFreeString(BSTR bstr)
HRESULT bCap_CommandGetParameters(int fd, uint32_t hCommand, VARIANT *pVal)
#define ID_COMMAND_GETATTRIBUTE
HRESULT bCap_TaskGetID(int fd, uint32_t hTask, VARIANT *pVal)
#define ID_TASK_GETVARIABLE
HRESULT bCap_FilePutValue(int fd, uint32_t hFile, VARIANT newVal)
HRESULT bCap_ControllerGetAttribute(int fd, uint32_t hController, int32_t *pVal)
HRESULT bCap_VariableGetAttribute(int fd, uint32_t hVariable, int32_t *pVal)
#define ID_VARIABLE_GETVALUE
#define ID_CONTROLLER_GETROBOTNAMES
bool CallFunction(bcap::Request &req, bcap::Response &res)
HRESULT bCap_RobotGetID(int fd, uint32_t hRobot, VARIANT *pVal)
HRESULT bCap_MessageClear(int fd, uint32_t hMessage)
#define ID_CONTROLLER_EXECUTE
HRESULT bCap_FilePutTag(int fd, uint32_t hFile, VARIANT newVal)
HRESULT bCap_ExtensionGetTag(int fd, uint32_t hExtension, VARIANT *pVal)
HRESULT bCap_CommandGetID(int fd, uint32_t hCommand, VARIANT *pVal)
HRESULT ConvertRacStr2Variant(uint16_t vt, const char *chSrc, VARIANT *pvargDest)
HRESULT bCap_MessageGetSource(int fd, uint32_t hMessage, BSTR *pVal)
HRESULT bCap_RobotPutTag(int fd, uint32_t hRobot, VARIANT newVal)
HRESULT bCap_ControllerGetVariableNames(int fd, uint32_t hController, BSTR bstrOption, VARIANT *pVal)
HRESULT bCap_SetTimeout(int fd, uint32_t timeout)
HRESULT bCap_RobotGoHome(int fd, uint32_t hRobot)
HRESULT bCap_ControllerGetVariable(int fd, uint32_t hController, BSTR bstrName, BSTR bstrOption, uint32_t *hVariable)
#define ID_CONTROLLER_PUTTAG
#define ID_EXTENSION_PUTID
#define ID_FILE_GETDATELASTMODIFIED
HRESULT bCap_VariableRelease(int fd, uint32_t *hVariable)
HRESULT bCap_ControllerGetTask(int fd, uint32_t hController, BSTR bstrName, BSTR bstrOption, uint32_t *hTask)
unsigned int get_Retry() const
HRESULT bCap_VariablePutValue(int fd, uint32_t hVariable, VARIANT newVal)
#define ID_TASK_GETVARIABLENAMES
HRESULT bCap_VariableGetMicrosecond(int fd, uint32_t hVariable, int32_t *pVal)
#define ID_CONTROLLER_CONNECT
HRESULT bCap_FileGetDateLastModified(int fd, uint32_t hFile, VARIANT *pVal)
#define ID_EXTENSION_GETID
HRESULT bCap_ExtensionPutID(int fd, uint32_t hExtension, VARIANT newVal)
HRESULT bCap_CommandExecute(int fd, uint32_t hCommand, int32_t lMode, VARIANT *pVal)
HRESULT bCap_ControllerGetCommandNames(int fd, uint32_t hController, BSTR bstrOption, VARIANT *pVal)
HRESULT bCap_ExtensionGetHelp(int fd, uint32_t hExtension, BSTR *pVal)
HRESULT bCap_FileGetFile(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption, uint32_t *hFile2)
HRESULT bCap_FileGetHelp(int fd, uint32_t hFile, BSTR *pVal)
#define ID_EXTENSION_GETATTRIBUTE
HRESULT StartService(ros::NodeHandle &node)
#define ID_FILE_GETFILENAMES
HRESULT bCap_TaskStop(int fd, uint32_t hTask, int32_t lMode, BSTR bstrOption)
HRESULT bCap_MessageReply(int fd, uint32_t hMessage, VARIANT vntData)
HRESULT ExecFunction(int32_t func_id, VARIANT_Vec &vntArgs, VARIANT_Ptr &vntRet)
HRESULT bCap_TaskGetTag(int fd, uint32_t hTask, VARIANT *pVal)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
HRESULT bCap_FileGetVariable(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption, uint32_t *hVariable)
HRESULT bCap_ServiceStop(int fd)
HRESULT bCap_FileGetType(int fd, uint32_t hFile, BSTR *pVal)
#define ID_MESSAGE_GETDATETIME
std::vector< VARIANT, VariantAllocator< VARIANT > > VARIANT_Vec
HRESULT bCap_RobotGetAttribute(int fd, uint32_t hRobot, int32_t *pVal)
HRESULT bCap_CommandGetTimeout(int fd, uint32_t hCommand, int32_t *pVal)
HRESULT bCap_CommandGetName(int fd, uint32_t hCommand, BSTR *pVal)
#define ID_MESSAGE_GETVALUE
HRESULT bCap_FileGetTag(int fd, uint32_t hFile, VARIANT *pVal)
#define ID_VARIABLE_GETHELP
HRESULT bCap_TaskGetName(int fd, uint32_t hTask, BSTR *pVal)
#define ID_EXTENSION_PUTTAG
int main(int argc, char **argv)
HRESULT bCap_RobotPutID(int fd, uint32_t hRobot, VARIANT newVal)
HRESULT bCap_RobotGetName(int fd, uint32_t hRobot, BSTR *pVal)
#define ID_VARIABLE_RELEASE
void put_Type(const std::string &type)
#define ID_ROBOT_GETATTRIBUTE
HRESULT bCap_RobotRelease(int fd, uint32_t *hRobot)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
HRESULT bCap_FileGetDateCreated(int fd, uint32_t hFile, VARIANT *pVal)
HRESULT bCap_Open_Client(const char *connect, uint32_t timeout, unsigned int retry, int *pfd)
#define ID_FILE_GETVARIABLENAMES
#define ID_VARIABLE_GETNAME
#define ID_CONTROLLER_GETMESSAGE
#define ID_TASK_GETFILENAME
HRESULT bCap_SetRetry(int fd, unsigned int retry)
HRESULT bCap_ControllerGetID(int fd, uint32_t hController, VARIANT *pVal)
HRESULT bCap_MessageGetValue(int fd, uint32_t hMessage, VARIANT *pVal)
HRESULT bCap_CommandGetHelp(int fd, uint32_t hCommand, BSTR *pVal)
HRESULT bCap_TaskPutTag(int fd, uint32_t hTask, VARIANT newVal)
HRESULT bCap_TaskGetHelp(int fd, uint32_t hTask, BSTR *pVal)
HRESULT bCap_RobotUnchuck(int fd, uint32_t hRobot, BSTR bstrOption)
#define ID_CONTROLLER_DISCONNECT
#define ID_COMMAND_GETSTATE
HRESULT bCap_RobotMove(int fd, uint32_t hRobot, int32_t lComp, VARIANT vntPose, BSTR bstrOption)
#define ID_MESSAGE_RELEASE
#define ID_COMMAND_GETPARAMETERS
HRESULT bCap_TaskExecute(int fd, uint32_t hTask, BSTR bstrCommand, VARIANT vntParam, VARIANT *pVal)
HRESULT bCap_CommandCancel(int fd, uint32_t hCommand)
HRESULT bCap_ControllerGetMessage(int fd, uint32_t hController, uint32_t *hMessage)
#define ID_EXTENSION_GETVARIABLE
HRESULT bCap_VariableGetTag(int fd, uint32_t hVariable, VARIANT *pVal)
HRESULT bCap_FileGetID(int fd, uint32_t hFile, VARIANT *pVal)
HRESULT bCap_FileGetAttribute(int fd, uint32_t hFile, int32_t *pVal)
HRESULT bCap_TaskPutID(int fd, uint32_t hTask, VARIANT newVal)
void put_Timeout(uint32_t value)
HRESULT bCap_ExtensionGetVariableNames(int fd, uint32_t hExtension, BSTR bstrOption, VARIANT *pVal)
HRESULT bCap_VariablePutID(int fd, uint32_t hVariable, VARIANT newVal)
#define ID_EXTENSION_RELEASE
void VariantInit(VARIANT *pvarg)
#define ID_ROBOT_ACCELERATE
HRESULT bCap_ControllerGetExtensionNames(int fd, uint32_t hController, BSTR bstrOption, VARIANT *pVal)
#define ID_VARIABLE_GETMICROSECOND
HRESULT bCap_FileGetName(int fd, uint32_t hFile, BSTR *pVal)
HRESULT bCap_RobotChuck(int fd, uint32_t hRobot, BSTR bstrOption)
HRESULT bCap_ServiceStart(int fd, BSTR bstrOption)
HRESULT bCap_RobotUnhold(int fd, uint32_t hRobot, BSTR bstrOption)
HRESULT bCap_RobotGetHelp(int fd, uint32_t hRobot, BSTR *pVal)
HRESULT bCap_ControllerGetCommand(int fd, uint32_t hController, BSTR bstrName, BSTR bstrOption, uint32_t *hCommand)
HRESULT bCap_ControllerGetHelp(int fd, uint32_t hController, BSTR *pVal)
#define ID_CONTROLLER_GETFILENAMES
HRESULT bCap_ControllerGetTaskNames(int fd, uint32_t hController, BSTR bstrOption, VARIANT *pVal)
#define ID_COMMAND_GETRESULT
HRESULT bCap_ExtensionRelease(int fd, uint32_t *hExtension)
#define ID_VARIABLE_GETATTRIBUTE
HRESULT bCap_TaskRelease(int fd, uint32_t *hTask)
HRESULT bCap_RobotExecute(int fd, uint32_t hRobot, BSTR bstrCommand, VARIANT vntParam, VARIANT *pVal)
#define ID_CONTROLLER_GETCOMMAND
HRESULT bCap_VariableGetName(int fd, uint32_t hVariable, BSTR *pVal)
#define ID_VARIABLE_GETDATETIME
BSTR SysAllocString(const wchar_t *sz)
#define ID_MESSAGE_GETSERIALNUMBER
#define ID_COMMAND_GETTIMEOUT
HRESULT bCap_MessageRelease(int fd, uint32_t *hMessage)
HRESULT bCap_CommandPutParameters(int fd, uint32_t hCommand, VARIANT newVal)
HRESULT bCap_FileGetVariableNames(int fd, uint32_t hFile, BSTR bstrOption, VARIANT *pVal)
#define ID_CONTROLLER_PUTID
HRESULT bCap_ControllerExecute(int fd, uint32_t hController, BSTR bstrCommand, VARIANT vntParam, VARIANT *pVal)
HRESULT ConvertVariant2RacStr(VARIANT varSrc, char **chDest)
#define ID_CONTROLLER_GETTAG
HRESULT bCap_VariablePutTag(int fd, uint32_t hVariable, VARIANT newVal)
#define ID_TASK_GETATTRIBUTE
boost::interprocess::unique_ptr< VARIANT, variant_deleter > VARIANT_Ptr
HRESULT bCap_ControllerPutID(int fd, uint32_t hController, VARIANT newVal)
HRESULT bCap_FileMove(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption)
HRESULT bCap_ControllerConnect(int fd, BSTR bstrName, BSTR bstrProvider, BSTR bstrMachine, BSTR bstrOption, uint32_t *hController)
HRESULT bCap_FilePutID(int fd, uint32_t hFile, VARIANT newVal)
#define ID_ROBOT_GETVARIABLENAMES
#define ID_MESSAGE_GETDESCRIPTION
HRESULT bCap_CommandGetState(int fd, uint32_t hCommand, int32_t *pVal)
HRESULT bCap_VariableGetID(int fd, uint32_t hVariable, VARIANT *pVal)
HRESULT bCap_FileDelete(int fd, uint32_t hFile, BSTR bstrOption)
#define ID_COMMAND_GETNAME
HRESULT bCap_ControllerGetName(int fd, uint32_t hController, BSTR *pVal)
HRESULT bCap_ControllerGetFileNames(int fd, uint32_t hController, BSTR bstrOption, VARIANT *pVal)
HRESULT bCap_ControllerGetTag(int fd, uint32_t hController, VARIANT *pVal)
#define ID_EXTENSION_GETNAME
HRESULT bCap_VariableGetHelp(int fd, uint32_t hVariable, BSTR *pVal)
#define ID_VARIABLE_PUTTAG
#define ID_ROBOT_GETVARIABLE
HRESULT bCap_CommandGetTag(int fd, uint32_t hCommand, VARIANT *pVal)
HRESULT bCap_RobotDrive(int fd, uint32_t hRobot, int32_t lNo, float fMov, BSTR bstrOption)
HRESULT bCap_CommandGetAttribute(int fd, uint32_t hCommand, int32_t *pVal)
HRESULT bCap_RobotAccelerate(int fd, uint32_t hRobot, int32_t lAxis, float fAccel, float fDecel)
HRESULT bCap_ExtensionGetAttribute(int fd, uint32_t hExtension, int32_t *pVal)
#define ID_CONTROLLER_GETTASKNAMES
HRESULT bCap_RobotGetVariable(int fd, uint32_t hRobot, BSTR bstrName, BSTR bstrOption, uint32_t *hVariable)
#define ID_VARIABLE_PUTVALUE
#define ID_FILE_GETDATELASTACCESSED
#define ID_COMMAND_RELEASE
HRESULT bCap_CommandGetResult(int fd, uint32_t hCommand, VARIANT *pVal)
HRESULT bCap_RobotHold(int fd, uint32_t hRobot, BSTR bstrOption)
#define ID_FILE_GETDATECREATED
HRESULT bCap_ControllerGetFile(int fd, uint32_t hController, BSTR bstrName, BSTR bstrOption, uint32_t *hFile)
HRESULT bCap_FileCopy(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption)
HRESULT bCap_ExtensionExecute(int fd, uint32_t hExtension, BSTR bstrCommand, VARIANT vntParam, VARIANT *pVal)
std::pair< int32_t, uint32_t > KeyHandle
#define ID_CONTROLLER_GETNAME
#define ID_EXTENSION_GETTAG
HRESULT bCap_CommandRelease(int fd, uint32_t *hCommand)
HRESULT bCap_CommandPutTag(int fd, uint32_t hCommand, VARIANT newVal)
HRESULT bCap_VariableGetValue(int fd, uint32_t hVariable, VARIANT *pVal)
HRESULT bCap_MessageGetSerialNumber(int fd, uint32_t hMessage, int32_t *pVal)
HRESULT bCap_FileExecute(int fd, uint32_t hFile, BSTR bstrCommand, VARIANT vntParam, VARIANT *pVal)
bool getParam(const std::string &key, std::string &s) const
HRESULT bCap_RobotRotate(int fd, uint32_t hRobot, VARIANT vntRotSuf, float fDeg, VARIANT vntPivot, BSTR bstrOption)
HRESULT bCap_Close_Client(int *pfd)
#define ID_MESSAGE_GETNUMBER
HRESULT bCap_FileRun(int fd, uint32_t hFile, BSTR bstrOption, BSTR *pVal)
#define ID_CONTROLLER_GETEXTENSION
HRESULT bCap_RobotSpeed(int fd, uint32_t hRobot, int32_t lAxis, float fSpeed)
#define ID_CONTROLLER_GETHELP
HRESULT bCap_GetRetry(int fd, unsigned int *retry)
#define ID_MESSAGE_GETDESTINATION
HRESULT bCap_GetTimeout(int fd, uint32_t *timeout)
HRESULT bCap_ControllerGetRobotNames(int fd, uint32_t hController, BSTR bstrOption, VARIANT *pVal)
HRESULT bCap_FileGetPath(int fd, uint32_t hFile, BSTR *pVal)
#define ID_COMMAND_PUTTIMEOUT
HRESULT bCap_TaskDelete(int fd, uint32_t hTask, BSTR bstrOption)
#define ID_COMMAND_GETTAG
#define ID_CONTROLLER_GETTASK
#define ID_CONTROLLER_GETROBOT
HRESULT bCap_RobotChange(int fd, uint32_t hRobot, BSTR bstrName)
#define ID_EXTENSION_GETHELP
HRESULT bCap_TaskGetAttribute(int fd, uint32_t hTask, int32_t *pVal)
HRESULT bCap_CommandPutTimeout(int fd, uint32_t hCommand, int32_t newVal)
HRESULT bCap_FileGetFileNames(int fd, uint32_t hFile, BSTR bstrOption, VARIANT *pVal)
#define ID_CONTROLLER_GETATTRIBUTE
HRESULT bCap_ControllerPutTag(int fd, uint32_t hController, VARIANT newVal)
#define ID_EXTENSION_EXECUTE
#define ID_CONTROLLER_GETVARIABLENAMES
uint32_t get_Timeout() const
#define ID_CONTROLLER_GETCOMMANDNAMES
#define ID_VARIABLE_GETTAG
#define ID_COMMAND_CANCEL
HRESULT bCap_FileGetValue(int fd, uint32_t hFile, VARIANT *pVal)
#define ID_CONTROLLER_GETFILE
#define ID_COMMAND_GETHELP
HRESULT bCap_RobotGetVariableNames(int fd, uint32_t hRobot, BSTR bstrOption, VARIANT *pVal)
#define ID_COMMAND_PUTPARAMETERS
HRESULT bCap_MessageGetDescription(int fd, uint32_t hMessage, BSTR *pVal)
HRESULT bCap_ExtensionGetID(int fd, uint32_t hExtension, VARIANT *pVal)
HRESULT bCap_MessageGetNumber(int fd, uint32_t hMessage, int32_t *pVal)
HRESULT bCap_ControllerGetRobot(int fd, uint32_t hController, BSTR bstrName, BSTR bstrOption, uint32_t *hRobot)
#define ID_FILE_GETVARIABLE
#define ID_CONTROLLER_GETID
#define ID_FILE_GETATTRIBUTE
#define ID_COMMAND_PUTTAG
HRESULT bCap_FileGetDateLastAccessed(int fd, uint32_t hFile, VARIANT *pVal)
HRESULT bCap_ControllerDisconnect(int fd, uint32_t *hController)
HRESULT bCap_MessageGetDestination(int fd, uint32_t hMessage, BSTR *pVal)
HRESULT bCap_VariableGetDateTime(int fd, uint32_t hVariable, VARIANT *pVal)
void put_Retry(unsigned int value)
HRESULT bCap_ExtensionGetName(int fd, uint32_t hExtension, BSTR *pVal)
HRESULT bCap_MessageGetDateTime(int fd, uint32_t hMessage, VARIANT *pVal)
#define ID_CONTROLLER_GETEXTENSIONNAMES
HRESULT bCap_FileRelease(int fd, uint32_t *hFile)
#define ID_VARIABLE_GETID
#define ID_EXTENSION_GETVARIABLENAMES
HRESULT bCap_ExtensionPutTag(int fd, uint32_t hExtension, VARIANT newVal)
#define ID_VARIABLE_PUTID
HRESULT bCap_TaskGetVariableNames(int fd, uint32_t hTask, BSTR bstrOption, VARIANT *pVal)
HRESULT bCap_FileGetSize(int fd, uint32_t hFile, int32_t *pVal)
#define ID_CONTROLLER_GETVARIABLE
HRESULT bCap_TaskGetFileName(int fd, uint32_t hTask, BSTR *pVal)
const std::string & get_Type() const
HRESULT bCap_TaskStart(int fd, uint32_t hTask, int32_t lMode, BSTR bstrOption)
HRESULT bCap_RobotGetTag(int fd, uint32_t hRobot, VARIANT *pVal)
#define ID_COMMAND_EXECUTE
HRESULT bCap_ExtensionGetVariable(int fd, uint32_t hExtension, BSTR bstrName, BSTR bstrOption, uint32_t *hVariable)