bcap_client.h
Go to the documentation of this file.
1 #ifndef BCAP_CLIENT_H_
2 #define BCAP_CLIENT_H_
3 
36 #ifndef _BCAP_EXP_CLIENT
37 #define _BCAP_EXP_CLIENT
38 #endif /* _BCAP_EXP_CLIENT */
39 
40 #include "../dn_common.h"
41 
47 #define BCAP_CONN_MAX (20)
48 
49 #ifdef __cplusplus
50 extern "C"
51 {
52 #endif
53 
63  bCap_Open_Client(const char *connect, uint32_t timeout, unsigned int retry,
64  int *pfd);
65 
72  bCap_Close_Client(int *pfd);
73 
81  bCap_SetTimeout(int fd, uint32_t timeout);
82 
90  bCap_GetTimeout(int fd, uint32_t *timeout);
91 
99  bCap_SetRetry(int fd, unsigned int retry);
100 
108  bCap_GetRetry(int fd, unsigned int *retry);
109 
117  bCap_ServiceStart(int fd, BSTR bstrOption);
118 
125  bCap_ServiceStop(int fd);
126 
138  bCap_ControllerConnect(int fd, BSTR bstrName, BSTR bstrProvider,
139  BSTR bstrMachine, BSTR bstrOption, uint32_t *hController);
140 
148  bCap_ControllerDisconnect(int fd, uint32_t *hController);
149 
160  bCap_ControllerGetExtension(int fd, uint32_t hController, BSTR bstrName,
161  BSTR bstrOption, uint32_t *hExtension);
162 
173  bCap_ControllerGetFile(int fd, uint32_t hController, BSTR bstrName,
174  BSTR bstrOption, uint32_t *hFile);
175 
186  bCap_ControllerGetRobot(int fd, uint32_t hController, BSTR bstrName,
187  BSTR bstrOption, uint32_t *hRobot);
188 
199  bCap_ControllerGetTask(int fd, uint32_t hController, BSTR bstrName,
200  BSTR bstrOption, uint32_t *hTask);
201 
212  bCap_ControllerGetVariable(int fd, uint32_t hController, BSTR bstrName,
213  BSTR bstrOption, uint32_t *hVariable);
214 
225  bCap_ControllerGetCommand(int fd, uint32_t hController, BSTR bstrName,
226  BSTR bstrOption, uint32_t *hCommand);
227 
237  bCap_ControllerGetExtensionNames(int fd, uint32_t hController,
238  BSTR bstrOption, VARIANT *pVal);
239 
249  bCap_ControllerGetFileNames(int fd, uint32_t hController, BSTR bstrOption,
250  VARIANT *pVal);
251 
261  bCap_ControllerGetRobotNames(int fd, uint32_t hController, BSTR bstrOption,
262  VARIANT *pVal);
263 
273  bCap_ControllerGetTaskNames(int fd, uint32_t hController, BSTR bstrOption,
274  VARIANT *pVal);
275 
285  bCap_ControllerGetVariableNames(int fd, uint32_t hController, BSTR bstrOption,
286  VARIANT *pVal);
287 
297  bCap_ControllerGetCommandNames(int fd, uint32_t hController, BSTR bstrOption,
298  VARIANT *pVal);
299 
310  bCap_ControllerExecute(int fd, uint32_t hController, BSTR bstrCommand,
311  VARIANT vntParam, VARIANT *pVal);
312 
321  bCap_ControllerGetMessage(int fd, uint32_t hController, uint32_t *hMessage);
322 
331  bCap_ControllerGetAttribute(int fd, uint32_t hController, int32_t *pVal);
332 
341  bCap_ControllerGetHelp(int fd, uint32_t hController, BSTR *pVal);
342 
351  bCap_ControllerGetName(int fd, uint32_t hController, BSTR *pVal);
352 
361  bCap_ControllerGetTag(int fd, uint32_t hController, VARIANT *pVal);
362 
371  bCap_ControllerPutTag(int fd, uint32_t hController, VARIANT newVal);
372 
381  bCap_ControllerGetID(int fd, uint32_t hController, VARIANT *pVal);
382 
391  bCap_ControllerPutID(int fd, uint32_t hController, VARIANT newVal);
392 
403  bCap_ExtensionGetVariable(int fd, uint32_t hExtension, BSTR bstrName,
404  BSTR bstrOption, uint32_t *hVariable);
405 
415  bCap_ExtensionGetVariableNames(int fd, uint32_t hExtension, BSTR bstrOption,
416  VARIANT *pVal);
417 
428  bCap_ExtensionExecute(int fd, uint32_t hExtension, BSTR bstrCommand,
429  VARIANT vntParam, VARIANT *pVal);
430 
439  bCap_ExtensionGetAttribute(int fd, uint32_t hExtension, int32_t *pVal);
440 
449  bCap_ExtensionGetHelp(int fd, uint32_t hExtension, BSTR *pVal);
450 
459  bCap_ExtensionGetName(int fd, uint32_t hExtension, BSTR *pVal);
460 
469  bCap_ExtensionGetTag(int fd, uint32_t hExtension, VARIANT *pVal);
470 
479  bCap_ExtensionPutTag(int fd, uint32_t hExtension, VARIANT newVal);
480 
489  bCap_ExtensionGetID(int fd, uint32_t hExtension, VARIANT *pVal);
490 
499  bCap_ExtensionPutID(int fd, uint32_t hExtension, VARIANT newVal);
500 
508  bCap_ExtensionRelease(int fd, uint32_t *hExtension);
509 
520  bCap_FileGetFile(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption,
521  uint32_t *hFile2);
522 
533  bCap_FileGetVariable(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption,
534  uint32_t *hVariable);
535 
545  bCap_FileGetFileNames(int fd, uint32_t hFile, BSTR bstrOption, VARIANT *pVal);
546 
556  bCap_FileGetVariableNames(int fd, uint32_t hFile, BSTR bstrOption,
557  VARIANT *pVal);
558 
569  bCap_FileExecute(int fd, uint32_t hFile, BSTR bstrCommand, VARIANT vntParam,
570  VARIANT *pVal);
571 
581  bCap_FileCopy(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption);
582 
591  bCap_FileDelete(int fd, uint32_t hFile, BSTR bstrOption);
592 
602  bCap_FileMove(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption);
603 
613  bCap_FileRun(int fd, uint32_t hFile, BSTR bstrOption, BSTR *pVal);
614 
623  bCap_FileGetDateCreated(int fd, uint32_t hFile, VARIANT *pVal);
624 
633  bCap_FileGetDateLastAccessed(int fd, uint32_t hFile, VARIANT *pVal);
634 
643  bCap_FileGetDateLastModified(int fd, uint32_t hFile, VARIANT *pVal);
644 
653  bCap_FileGetPath(int fd, uint32_t hFile, BSTR *pVal);
654 
663  bCap_FileGetSize(int fd, uint32_t hFile, int32_t *pVal);
664 
673  bCap_FileGetType(int fd, uint32_t hFile, BSTR *pVal);
674 
683  bCap_FileGetValue(int fd, uint32_t hFile, VARIANT *pVal);
684 
693  bCap_FilePutValue(int fd, uint32_t hFile, VARIANT newVal);
694 
703  bCap_FileGetAttribute(int fd, uint32_t hFile, int32_t *pVal);
704 
713  bCap_FileGetHelp(int fd, uint32_t hFile, BSTR *pVal);
714 
723  bCap_FileGetName(int fd, uint32_t hFile, BSTR *pVal);
724 
733  bCap_FileGetTag(int fd, uint32_t hFile, VARIANT *pVal);
734 
743  bCap_FilePutTag(int fd, uint32_t hFile, VARIANT newVal);
744 
753  bCap_FileGetID(int fd, uint32_t hFile, VARIANT *pVal);
754 
763  bCap_FilePutID(int fd, uint32_t hFile, VARIANT newVal);
764 
772  bCap_FileRelease(int fd, uint32_t *hFile);
773 
784  bCap_RobotGetVariable(int fd, uint32_t hRobot, BSTR bstrName, BSTR bstrOption,
785  uint32_t *hVariable);
786 
796  bCap_RobotGetVariableNames(int fd, uint32_t hRobot, BSTR bstrOption,
797  VARIANT *pVal);
798 
809  bCap_RobotExecute(int fd, uint32_t hRobot, BSTR bstrCommand, VARIANT vntParam,
810  VARIANT *pVal);
811 
822  bCap_RobotAccelerate(int fd, uint32_t hRobot, int32_t lAxis, float fAccel,
823  float fDecel);
824 
833  bCap_RobotChange(int fd, uint32_t hRobot, BSTR bstrName);
834 
843  bCap_RobotChuck(int fd, uint32_t hRobot, BSTR bstrOption);
844 
855  bCap_RobotDrive(int fd, uint32_t hRobot, int32_t lNo, float fMov,
856  BSTR bstrOption);
857 
865  bCap_RobotGoHome(int fd, uint32_t hRobot);
866 
875  bCap_RobotHalt(int fd, uint32_t hRobot, BSTR bstrOption);
876 
885  bCap_RobotHold(int fd, uint32_t hRobot, BSTR bstrOption);
886 
897  bCap_RobotMove(int fd, uint32_t hRobot, int32_t lComp, VARIANT vntPose,
898  BSTR bstrOption);
899 
911  bCap_RobotRotate(int fd, uint32_t hRobot, VARIANT vntRotSuf, float fDeg,
912  VARIANT vntPivot, BSTR bstrOption);
913 
923  bCap_RobotSpeed(int fd, uint32_t hRobot, int32_t lAxis, float fSpeed);
924 
933  bCap_RobotUnchuck(int fd, uint32_t hRobot, BSTR bstrOption);
934 
943  bCap_RobotUnhold(int fd, uint32_t hRobot, BSTR bstrOption);
944 
953  bCap_RobotGetAttribute(int fd, uint32_t hRobot, int32_t *pVal);
954 
963  bCap_RobotGetHelp(int fd, uint32_t hRobot, BSTR *pVal);
964 
973  bCap_RobotGetName(int fd, uint32_t hRobot, BSTR *pVal);
974 
983  bCap_RobotGetTag(int fd, uint32_t hRobot, VARIANT *pVal);
984 
993  bCap_RobotPutTag(int fd, uint32_t hRobot, VARIANT newVal);
994 
1003  bCap_RobotGetID(int fd, uint32_t hRobot, VARIANT *pVal);
1004 
1013  bCap_RobotPutID(int fd, uint32_t hRobot, VARIANT newVal);
1014 
1022  bCap_RobotRelease(int fd, uint32_t *hRobot);
1023 
1034  bCap_TaskGetVariable(int fd, uint32_t hTask, BSTR bstrName, BSTR bstrOption,
1035  uint32_t *hVariable);
1036 
1046  bCap_TaskGetVariableNames(int fd, uint32_t hTask, BSTR bstrOption,
1047  VARIANT *pVal);
1048 
1059  bCap_TaskExecute(int fd, uint32_t hTask, BSTR bstrCommand, VARIANT vntParam,
1060  VARIANT *pVal);
1061 
1071  bCap_TaskStart(int fd, uint32_t hTask, int32_t lMode, BSTR bstrOption);
1072 
1082  bCap_TaskStop(int fd, uint32_t hTask, int32_t lMode, BSTR bstrOption);
1083 
1092  bCap_TaskDelete(int fd, uint32_t hTask, BSTR bstrOption);
1093 
1102  bCap_TaskGetFileName(int fd, uint32_t hTask, BSTR *pVal);
1103 
1112  bCap_TaskGetAttribute(int fd, uint32_t hTask, int32_t *pVal);
1113 
1122  bCap_TaskGetHelp(int fd, uint32_t hTask, BSTR *pVal);
1123 
1132  bCap_TaskGetName(int fd, uint32_t hTask, BSTR *pVal);
1133 
1142  bCap_TaskGetTag(int fd, uint32_t hTask, VARIANT *pVal);
1143 
1152  bCap_TaskPutTag(int fd, uint32_t hTask, VARIANT newVal);
1153 
1162  bCap_TaskGetID(int fd, uint32_t hTask, VARIANT *pVal);
1163 
1172  bCap_TaskPutID(int fd, uint32_t hTask, VARIANT newVal);
1173 
1181  bCap_TaskRelease(int fd, uint32_t *hTask);
1182 
1191  bCap_VariableGetDateTime(int fd, uint32_t hVariable, VARIANT *pVal);
1192 
1201  bCap_VariableGetValue(int fd, uint32_t hVariable, VARIANT *pVal);
1202 
1211  bCap_VariablePutValue(int fd, uint32_t hVariable, VARIANT newVal);
1212 
1221  bCap_VariableGetAttribute(int fd, uint32_t hVariable, int32_t *pVal);
1222 
1231  bCap_VariableGetHelp(int fd, uint32_t hVariable, BSTR *pVal);
1232 
1241  bCap_VariableGetName(int fd, uint32_t hVariable, BSTR *pVal);
1242 
1251  bCap_VariableGetTag(int fd, uint32_t hVariable, VARIANT *pVal);
1252 
1261  bCap_VariablePutTag(int fd, uint32_t hVariable, VARIANT newVal);
1262 
1271  bCap_VariableGetID(int fd, uint32_t hVariable, VARIANT *pVal);
1272 
1281  bCap_VariablePutID(int fd, uint32_t hVariable, VARIANT newVal);
1282 
1291  bCap_VariableGetMicrosecond(int fd, uint32_t hVariable, int32_t *pVal);
1292 
1300  bCap_VariableRelease(int fd, uint32_t *hVariable);
1301 
1311  bCap_CommandExecute(int fd, uint32_t hCommand, int32_t lMode, VARIANT *pVal);
1312 
1320  bCap_CommandCancel(int fd, uint32_t hCommand);
1321 
1330  bCap_CommandGetTimeout(int fd, uint32_t hCommand, int32_t *pVal);
1331 
1340  bCap_CommandPutTimeout(int fd, uint32_t hCommand, int32_t newVal);
1341 
1350  bCap_CommandGetState(int fd, uint32_t hCommand, int32_t *pVal);
1351 
1360  bCap_CommandGetParameters(int fd, uint32_t hCommand, VARIANT *pVal);
1361 
1370  bCap_CommandPutParameters(int fd, uint32_t hCommand, VARIANT newVal);
1371 
1380  bCap_CommandGetResult(int fd, uint32_t hCommand, VARIANT *pVal);
1381 
1390  bCap_CommandGetAttribute(int fd, uint32_t hCommand, int32_t *pVal);
1391 
1400  bCap_CommandGetHelp(int fd, uint32_t hCommand, BSTR *pVal);
1401 
1410  bCap_CommandGetName(int fd, uint32_t hCommand, BSTR *pVal);
1411 
1420  bCap_CommandGetTag(int fd, uint32_t hCommand, VARIANT *pVal);
1421 
1430  bCap_CommandPutTag(int fd, uint32_t hCommand, VARIANT newVal);
1431 
1440  bCap_CommandGetID(int fd, uint32_t hCommand, VARIANT *pVal);
1441 
1450  bCap_CommandPutID(int fd, uint32_t hCommand, VARIANT newVal);
1451 
1459  bCap_CommandRelease(int fd, uint32_t *hCommand);
1460 
1469  bCap_MessageReply(int fd, uint32_t hMessage, VARIANT vntData);
1470 
1478  bCap_MessageClear(int fd, uint32_t hMessage);
1479 
1488  bCap_MessageGetDateTime(int fd, uint32_t hMessage, VARIANT *pVal);
1489 
1498  bCap_MessageGetDescription(int fd, uint32_t hMessage, BSTR *pVal);
1499 
1508  bCap_MessageGetDestination(int fd, uint32_t hMessage, BSTR *pVal);
1509 
1518  bCap_MessageGetNumber(int fd, uint32_t hMessage, int32_t *pVal);
1519 
1528  bCap_MessageGetSerialNumber(int fd, uint32_t hMessage, int32_t *pVal);
1529 
1538  bCap_MessageGetSource(int fd, uint32_t hMessage, BSTR *pVal);
1539 
1548  bCap_MessageGetValue(int fd, uint32_t hMessage, VARIANT *pVal);
1549 
1557  bCap_MessageRelease(int fd, uint32_t *hMessage);
1558 
1559 #ifdef __cplusplus
1560 }
1561 #endif
1562 
1563 #endif /* BCAP_CLIENT_H_ */
_BCAP_EXP_CLIENT HRESULT bCap_CommandGetResult(int fd, uint32_t hCommand, VARIANT *pVal)
Send the b-CAP ID_COMMAND_GETRESULT packet.
Definition: bcap_client.c:1590
_BCAP_EXP_CLIENT HRESULT bCap_FileGetAttribute(int fd, uint32_t hFile, int32_t *pVal)
Send the b-CAP ID_FILE_GETATTRIBUTE packet.
Definition: bcap_client.c:1065
_BCAP_EXP_CLIENT HRESULT bCap_CommandGetID(int fd, uint32_t hCommand, VARIANT *pVal)
Send the b-CAP ID_COMMAND_GETID packet.
Definition: bcap_client.c:1632
_BCAP_EXP_CLIENT HRESULT bCap_RobotGetVariable(int fd, uint32_t hRobot, BSTR bstrName, BSTR bstrOption, uint32_t *hVariable)
Send the b-CAP ID_ROBOT_GETVARIABLE packet.
Definition: bcap_client.c:1131
_BCAP_EXP_CLIENT HRESULT bCap_RobotUnhold(int fd, uint32_t hRobot, BSTR bstrOption)
Send the b-CAP ID_ROBOT_UNHOLD packet.
Definition: bcap_client.c:1245
_BCAP_EXP_CLIENT HRESULT bCap_CommandGetParameters(int fd, uint32_t hCommand, VARIANT *pVal)
Send the b-CAP ID_COMMAND_GETPARAMETERS packet.
Definition: bcap_client.c:1574
_BCAP_EXP_CLIENT HRESULT bCap_MessageClear(int fd, uint32_t hMessage)
Send the b-CAP ID_MESSAGE_CLEAR packet.
Definition: bcap_client.c:1670
unsigned uint32_t
Definition: stdint.h:43
_BCAP_EXP_CLIENT HRESULT bCap_ControllerGetExtensionNames(int fd, uint32_t hController, BSTR bstrOption, VARIANT *pVal)
Send the b-CAP ID_CONTROLLER_GETEXTENSIONNAMES packet.
Definition: bcap_client.c:706
_BCAP_EXP_CLIENT HRESULT bCap_FileCopy(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption)
Send the b-CAP ID_FILE_COPY packet.
Definition: bcap_client.c:977
_BCAP_EXP_CLIENT HRESULT bCap_ExtensionGetName(int fd, uint32_t hExtension, BSTR *pVal)
Send the b-CAP ID_EXTENSION_GETNAME packet.
Definition: bcap_client.c:877
_BCAP_EXP_CLIENT HRESULT bCap_ExtensionRelease(int fd, uint32_t *hExtension)
Send the b-CAP ID_EXTENSION_RELEASE packet.
Definition: bcap_client.c:912
_BCAP_EXP_CLIENT HRESULT bCap_VariableGetID(int fd, uint32_t hVariable, VARIANT *pVal)
Send the b-CAP ID_VARIABLE_GETID packet.
Definition: bcap_client.c:1499
_BCAP_EXP_CLIENT HRESULT bCap_FileGetName(int fd, uint32_t hFile, BSTR *pVal)
Send the b-CAP ID_FILE_GETNAME packet.
Definition: bcap_client.c:1079
_BCAP_EXP_CLIENT HRESULT bCap_RobotPutID(int fd, uint32_t hRobot, VARIANT newVal)
Send the b-CAP ID_ROBOT_PUTID packet.
Definition: bcap_client.c:1294
_BCAP_EXP_CLIENT HRESULT bCap_TaskGetVariableNames(int fd, uint32_t hTask, BSTR bstrOption, VARIANT *pVal)
Send the b-CAP ID_TASK_GETVARIABLENAMES packet.
Definition: bcap_client.c:1329
_BCAP_EXP_CLIENT HRESULT bCap_TaskDelete(int fd, uint32_t hTask, BSTR bstrOption)
Send the b-CAP ID_TASK_DELETE packet.
Definition: bcap_client.c:1361
_BCAP_EXP_CLIENT HRESULT bCap_MessageRelease(int fd, uint32_t *hMessage)
Send the b-CAP ID_MESSAGE_RELEASE packet.
Definition: bcap_client.c:1729
_BCAP_EXP_CLIENT HRESULT bCap_RobotGetTag(int fd, uint32_t hRobot, VARIANT *pVal)
Send the b-CAP ID_ROBOT_GETTAG packet.
Definition: bcap_client.c:1273
_BCAP_EXP_CLIENT HRESULT bCap_CommandGetName(int fd, uint32_t hCommand, BSTR *pVal)
Send the b-CAP ID_COMMAND_GETNAME packet.
Definition: bcap_client.c:1611
_BCAP_EXP_CLIENT HRESULT bCap_TaskGetName(int fd, uint32_t hTask, BSTR *pVal)
Send the b-CAP ID_TASK_GETNAME packet.
Definition: bcap_client.c:1389
_BCAP_EXP_CLIENT HRESULT bCap_RobotGetAttribute(int fd, uint32_t hRobot, int32_t *pVal)
Send the b-CAP ID_ROBOT_GETATTRIBUTE packet.
Definition: bcap_client.c:1252
_BCAP_EXP_CLIENT HRESULT bCap_RobotGoHome(int fd, uint32_t hRobot)
Send the b-CAP ID_ROBOT_GOHOME packet.
Definition: bcap_client.c:1192
_BCAP_EXP_CLIENT HRESULT bCap_FileGetDateLastAccessed(int fd, uint32_t hFile, VARIANT *pVal)
Send the b-CAP ID_FILE_GETDATELASTACCESSED packet.
Definition: bcap_client.c:1014
_BCAP_EXP_CLIENT HRESULT bCap_ControllerGetRobot(int fd, uint32_t hController, BSTR bstrName, BSTR bstrOption, uint32_t *hRobot)
Send the b-CAP ID_CONTROLLER_GETROBOT packet.
Definition: bcap_client.c:662
_BCAP_EXP_CLIENT HRESULT bCap_FileGetFile(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption, uint32_t *hFile2)
Send the b-CAP ID_FILE_GETFILE packet.
Definition: bcap_client.c:929
_BCAP_EXP_CLIENT HRESULT bCap_CommandPutTimeout(int fd, uint32_t hCommand, int32_t newVal)
Send the b-CAP ID_COMMAND_PUTTIMEOUT packet.
Definition: bcap_client.c:1560
_BCAP_EXP_CLIENT HRESULT bCap_ControllerGetTaskNames(int fd, uint32_t hController, BSTR bstrOption, VARIANT *pVal)
Send the b-CAP ID_CONTROLLER_GETTASKNAMES packet.
Definition: bcap_client.c:733
wchar_t * BSTR
Definition: dn_common.h:239
_BCAP_EXP_CLIENT HRESULT bCap_FileGetVariable(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption, uint32_t *hVariable)
Send the b-CAP ID_FILE_GETVARIABLE packet.
Definition: bcap_client.c:940
_BCAP_EXP_CLIENT HRESULT bCap_MessageReply(int fd, uint32_t hMessage, VARIANT vntData)
Send the b-CAP ID_MESSAGE_REPLY packet.
Definition: bcap_client.c:1663
_BCAP_EXP_CLIENT HRESULT bCap_ControllerGetCommandNames(int fd, uint32_t hController, BSTR bstrOption, VARIANT *pVal)
Send the b-CAP ID_CONTROLLER_GETCOMMANDNAMES packet.
Definition: bcap_client.c:751
_BCAP_EXP_CLIENT HRESULT bCap_ExtensionGetVariable(int fd, uint32_t hExtension, BSTR bstrName, BSTR bstrOption, uint32_t *hVariable)
Send the b-CAP ID_EXTENSION_GETVARIABLE packet.
Definition: bcap_client.c:833
_BCAP_EXP_CLIENT HRESULT bCap_MessageGetDescription(int fd, uint32_t hMessage, BSTR *pVal)
Send the b-CAP ID_MESSAGE_GETDESCRIPTION packet.
Definition: bcap_client.c:1684
_BCAP_EXP_CLIENT HRESULT bCap_FileDelete(int fd, uint32_t hFile, BSTR bstrOption)
Send the b-CAP ID_FILE_DELETE packet.
Definition: bcap_client.c:985
_BCAP_EXP_CLIENT HRESULT bCap_CommandPutParameters(int fd, uint32_t hCommand, VARIANT newVal)
Send the b-CAP ID_VARIABLE_PUTPARAMETERS packet.
Definition: bcap_client.c:1582
_BCAP_EXP_CLIENT HRESULT bCap_ExtensionGetVariableNames(int fd, uint32_t hExtension, BSTR bstrOption, VARIANT *pVal)
Send the b-CAP ID_EXTENSION_GETVARIABLENAMES packet.
Definition: bcap_client.c:844
_BCAP_EXP_CLIENT HRESULT bCap_ControllerGetFile(int fd, uint32_t hController, BSTR bstrName, BSTR bstrOption, uint32_t *hFile)
Send the b-CAP ID_CONTROLLER_GETFILE packet.
Definition: bcap_client.c:651
_BCAP_EXP_CLIENT HRESULT bCap_FileMove(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption)
Send the b-CAP ID_FILE_MOVE packet.
Definition: bcap_client.c:992
_BCAP_EXP_CLIENT HRESULT bCap_MessageGetNumber(int fd, uint32_t hMessage, int32_t *pVal)
Send the b-CAP ID_MESSAGE_GETNUMBER packet.
Definition: bcap_client.c:1700
_BCAP_EXP_CLIENT HRESULT bCap_ServiceStart(int fd, BSTR bstrOption)
Send the b-CAP ID_SERVICE_START packet.
Definition: bcap_client.c:598
_BCAP_EXP_CLIENT HRESULT bCap_FileRun(int fd, uint32_t hFile, BSTR bstrOption, BSTR *pVal)
Send the b-CAP ID_FILE_RUN packet.
Definition: bcap_client.c:1000
_BCAP_EXP_CLIENT HRESULT bCap_VariableRelease(int fd, uint32_t *hVariable)
Send the b-CAP ID_VARIABLE_RELEASE packet.
Definition: bcap_client.c:1521
_BCAP_EXP_CLIENT HRESULT bCap_MessageGetSerialNumber(int fd, uint32_t hMessage, int32_t *pVal)
Send the b-CAP ID_MESSAGE_GETSERIALNUMBER packet.
Definition: bcap_client.c:1707
_BCAP_EXP_CLIENT HRESULT bCap_TaskStart(int fd, uint32_t hTask, int32_t lMode, BSTR bstrOption)
Send the b-CAP ID_TASK_START packet.
Definition: bcap_client.c:1347
_BCAP_EXP_CLIENT HRESULT bCap_RobotGetHelp(int fd, uint32_t hRobot, BSTR *pVal)
Send the b-CAP ID_ROBOT_GETHELP packet.
Definition: bcap_client.c:1259
_BCAP_EXP_CLIENT HRESULT bCap_ControllerExecute(int fd, uint32_t hController, BSTR bstrCommand, VARIANT vntParam, VARIANT *pVal)
Send the b-CAP ID_CONTROLLER_EXECUTE packet.
Definition: bcap_client.c:760
_BCAP_EXP_CLIENT HRESULT bCap_TaskGetHelp(int fd, uint32_t hTask, BSTR *pVal)
Send the b-CAP ID_TASK_GETHELP packet.
Definition: bcap_client.c:1382
_BCAP_EXP_CLIENT HRESULT bCap_CommandExecute(int fd, uint32_t hCommand, int32_t lMode, VARIANT *pVal)
Send the b-CAP ID_COMMAND_EXECUTE packet.
Definition: bcap_client.c:1538
_BCAP_EXP_CLIENT HRESULT bCap_ExtensionGetAttribute(int fd, uint32_t hExtension, int32_t *pVal)
Send the b-CAP ID_EXTENSION_GETATTRIBUTE packet.
Definition: bcap_client.c:862
_BCAP_EXP_CLIENT HRESULT bCap_ControllerDisconnect(int fd, uint32_t *hController)
Send the b-CAP ID_CONTROLLER_DISCONNECT packet.
Definition: bcap_client.c:623
_BCAP_EXP_CLIENT HRESULT bCap_ControllerGetFileNames(int fd, uint32_t hController, BSTR bstrOption, VARIANT *pVal)
Send the b-CAP ID_CONTROLLER_GETFILENAMES packet.
Definition: bcap_client.c:715
_BCAP_EXP_CLIENT HRESULT bCap_CommandGetTimeout(int fd, uint32_t hCommand, int32_t *pVal)
Send the b-CAP ID_COMMAND_GETTIMEOUT packet.
Definition: bcap_client.c:1553
_BCAP_EXP_CLIENT HRESULT bCap_CommandGetState(int fd, uint32_t hCommand, int32_t *pVal)
Send the b-CAP ID_COMMAND_GETSTATE packet.
Definition: bcap_client.c:1567
_BCAP_EXP_CLIENT HRESULT bCap_ControllerPutID(int fd, uint32_t hController, VARIANT newVal)
Send the b-CAP ID_CONTROLLER_PUTID packet.
Definition: bcap_client.c:825
_BCAP_EXP_CLIENT HRESULT bCap_VariableGetDateTime(int fd, uint32_t hVariable, VARIANT *pVal)
Send the b-CAP ID_VARIABLE_GETDATETIME packet.
Definition: bcap_client.c:1441
_BCAP_EXP_CLIENT HRESULT bCap_ControllerGetTag(int fd, uint32_t hController, VARIANT *pVal)
Send the b-CAP ID_CONTROLLER_GETTAG packet.
Definition: bcap_client.c:803
_BCAP_EXP_CLIENT HRESULT bCap_TaskGetTag(int fd, uint32_t hTask, VARIANT *pVal)
Send the b-CAP ID_TASK_GETTAG packet.
Definition: bcap_client.c:1396
_BCAP_EXP_CLIENT HRESULT bCap_RobotHalt(int fd, uint32_t hRobot, BSTR bstrOption)
Send the b-CAP ID_ROBOT_HALT packet.
Definition: bcap_client.c:1199
_BCAP_EXP_CLIENT HRESULT bCap_ControllerGetCommand(int fd, uint32_t hController, BSTR bstrName, BSTR bstrOption, uint32_t *hCommand)
Send the b-CAP ID_CONTROLLER_GETCOMMAND packet.
Definition: bcap_client.c:695
_BCAP_EXP_CLIENT HRESULT bCap_RobotUnchuck(int fd, uint32_t hRobot, BSTR bstrOption)
Send the b-CAP ID_ROBOT_UNCHUCK packet.
Definition: bcap_client.c:1238
_BCAP_EXP_CLIENT HRESULT bCap_Open_Client(const char *connect, uint32_t timeout, unsigned int retry, int *pfd)
Starts b-CAP communication.
Definition: bcap_client.c:322
int32_t HRESULT
Definition: dn_common.h:61
_BCAP_EXP_CLIENT HRESULT bCap_TaskGetAttribute(int fd, uint32_t hTask, int32_t *pVal)
Send the b-CAP ID_TASK_GETATTRIBUTE packet.
Definition: bcap_client.c:1375
_BCAP_EXP_CLIENT HRESULT bCap_RobotAccelerate(int fd, uint32_t hRobot, int32_t lAxis, float fAccel, float fDecel)
Send the b-CAP ID_ROBOT_ACCELERATE packet.
Definition: bcap_client.c:1160
_BCAP_EXP_CLIENT HRESULT bCap_RobotChuck(int fd, uint32_t hRobot, BSTR bstrOption)
Send the b-CAP ID_ROBOT_CHUCK packet.
Definition: bcap_client.c:1176
#define _BCAP_EXP_CLIENT
Definition: bcap_client.h:37
_BCAP_EXP_CLIENT HRESULT bCap_FileGetVariableNames(int fd, uint32_t hFile, BSTR bstrOption, VARIANT *pVal)
Send the b-CAP ID_FILE_GETVARIABLENAMES packet.
Definition: bcap_client.c:959
_BCAP_EXP_CLIENT HRESULT bCap_RobotExecute(int fd, uint32_t hRobot, BSTR bstrCommand, VARIANT vntParam, VARIANT *pVal)
Send the b-CAP ID_ROBOT_EXECUTE packet.
Definition: bcap_client.c:1151
_BCAP_EXP_CLIENT HRESULT bCap_ExtensionExecute(int fd, uint32_t hExtension, BSTR bstrCommand, VARIANT vntParam, VARIANT *pVal)
Send the b-CAP ID_EXTENSION_EXECUTE packet.
Definition: bcap_client.c:853
_BCAP_EXP_CLIENT HRESULT bCap_RobotRotate(int fd, uint32_t hRobot, VARIANT vntRotSuf, float fDeg, VARIANT vntPivot, BSTR bstrOption)
Send the b-CAP ID_ROBOT_ROTATE packet.
Definition: bcap_client.c:1222
_BCAP_EXP_CLIENT HRESULT bCap_CommandGetAttribute(int fd, uint32_t hCommand, int32_t *pVal)
Send the b-CAP ID_COMMAND_GETATTRIBUTE packet.
Definition: bcap_client.c:1597
_BCAP_EXP_CLIENT HRESULT bCap_ControllerGetID(int fd, uint32_t hController, VARIANT *pVal)
Send the b-CAP ID_CONTROLLER_GETID packet.
Definition: bcap_client.c:818
_BCAP_EXP_CLIENT HRESULT bCap_TaskPutTag(int fd, uint32_t hTask, VARIANT newVal)
Send the b-CAP ID_TASK_PUTTAG packet.
Definition: bcap_client.c:1403
_BCAP_EXP_CLIENT HRESULT bCap_CommandRelease(int fd, uint32_t *hCommand)
Send the b-CAP ID_COMMAND_RELEASE packet.
Definition: bcap_client.c:1646
_BCAP_EXP_CLIENT HRESULT bCap_RobotChange(int fd, uint32_t hRobot, BSTR bstrName)
Send the b-CAP ID_ROBOT_CHANGE packet.
Definition: bcap_client.c:1169
_BCAP_EXP_CLIENT HRESULT bCap_FileGetHelp(int fd, uint32_t hFile, BSTR *pVal)
Send the b-CAP ID_FILE_GETHELP packet.
Definition: bcap_client.c:1072
_BCAP_EXP_CLIENT HRESULT bCap_ControllerConnect(int fd, BSTR bstrName, BSTR bstrProvider, BSTR bstrMachine, BSTR bstrOption, uint32_t *hController)
Send the b-CAP ID_CONTROLLER_CONNECT packet.
Definition: bcap_client.c:612
_BCAP_EXP_CLIENT HRESULT bCap_FileExecute(int fd, uint32_t hFile, BSTR bstrCommand, VARIANT vntParam, VARIANT *pVal)
Send the b-CAP ID_FILE_EXECUTE packet.
Definition: bcap_client.c:968
_BCAP_EXP_CLIENT HRESULT bCap_CommandGetTag(int fd, uint32_t hCommand, VARIANT *pVal)
Send the b-CAP ID_COMMAND_GETTAG packet.
Definition: bcap_client.c:1618
_BCAP_EXP_CLIENT HRESULT bCap_FileRelease(int fd, uint32_t *hFile)
Send the b-CAP ID_FILE_RELEASE packet.
Definition: bcap_client.c:1114
_BCAP_EXP_CLIENT HRESULT bCap_FileGetPath(int fd, uint32_t hFile, BSTR *pVal)
Send the b-CAP ID_FILE_GETPATH packet.
Definition: bcap_client.c:1030
_BCAP_EXP_CLIENT HRESULT bCap_VariableGetTag(int fd, uint32_t hVariable, VARIANT *pVal)
Send the b-CAP ID_VARIABLE_GETTAG packet.
Definition: bcap_client.c:1485
_BCAP_EXP_CLIENT HRESULT bCap_RobotRelease(int fd, uint32_t *hRobot)
Send the b-CAP ID_ROBOT_RELEASE packet.
Definition: bcap_client.c:1301
_BCAP_EXP_CLIENT HRESULT bCap_FileGetDateLastModified(int fd, uint32_t hFile, VARIANT *pVal)
Send the b-CAP ID_FILE_GETDATELASTMODIFIED packet.
Definition: bcap_client.c:1022
_BCAP_EXP_CLIENT HRESULT bCap_RobotHold(int fd, uint32_t hRobot, BSTR bstrOption)
Send the b-CAP ID_ROBOT_HOLD packet.
Definition: bcap_client.c:1206
_BCAP_EXP_CLIENT HRESULT bCap_FileGetFileNames(int fd, uint32_t hFile, BSTR bstrOption, VARIANT *pVal)
Send the b-CAP ID_FILE_GETFILENAMES packet.
Definition: bcap_client.c:951
_BCAP_EXP_CLIENT HRESULT bCap_RobotPutTag(int fd, uint32_t hRobot, VARIANT newVal)
Send the b-CAP ID_ROBOT_PUTTAG packet.
Definition: bcap_client.c:1280
_BCAP_EXP_CLIENT HRESULT bCap_VariableGetValue(int fd, uint32_t hVariable, VARIANT *pVal)
Send the b-CAP ID_VARIABLE_GETVALUE packet.
Definition: bcap_client.c:1449
_BCAP_EXP_CLIENT HRESULT bCap_ExtensionPutID(int fd, uint32_t hExtension, VARIANT newVal)
Send the b-CAP ID_EXTENSION_PUTID packet.
Definition: bcap_client.c:905
_BCAP_EXP_CLIENT HRESULT bCap_MessageGetDateTime(int fd, uint32_t hMessage, VARIANT *pVal)
Send the b-CAP ID_MESSAGE_GETDATETIME packet.
Definition: bcap_client.c:1677
_BCAP_EXP_CLIENT HRESULT bCap_ControllerGetTask(int fd, uint32_t hController, BSTR bstrName, BSTR bstrOption, uint32_t *hTask)
Send the b-CAP ID_CONTROLLER_GETTASK packet.
Definition: bcap_client.c:673
_BCAP_EXP_CLIENT HRESULT bCap_RobotMove(int fd, uint32_t hRobot, int32_t lComp, VARIANT vntPose, BSTR bstrOption)
Send the b-CAP ID_ROBOT_MOVE packet.
Definition: bcap_client.c:1213
_BCAP_EXP_CLIENT HRESULT bCap_VariableGetAttribute(int fd, uint32_t hVariable, int32_t *pVal)
Send the b-CAP ID_VARIABLE_GETATTRIBUTE packet.
Definition: bcap_client.c:1463
_BCAP_EXP_CLIENT HRESULT bCap_RobotGetVariableNames(int fd, uint32_t hRobot, BSTR bstrOption, VARIANT *pVal)
Send the b-CAP ID_ROBOT_GETVARIABLENAMES packet.
Definition: bcap_client.c:1142
_BCAP_EXP_CLIENT HRESULT bCap_ExtensionGetHelp(int fd, uint32_t hExtension, BSTR *pVal)
Send the b-CAP ID_EXTENSION_GETHELP packet.
Definition: bcap_client.c:870
_BCAP_EXP_CLIENT HRESULT bCap_ControllerGetRobotNames(int fd, uint32_t hController, BSTR bstrOption, VARIANT *pVal)
Send the b-CAP ID_CONTROLLER_GETROBOTNAMES packet.
Definition: bcap_client.c:724
_BCAP_EXP_CLIENT HRESULT bCap_ControllerGetName(int fd, uint32_t hController, BSTR *pVal)
Send the b-CAP ID_CONTROLLER_GETNAME packet.
Definition: bcap_client.c:795
_BCAP_EXP_CLIENT HRESULT bCap_ControllerGetVariableNames(int fd, uint32_t hController, BSTR bstrOption, VARIANT *pVal)
Send the b-CAP ID_CONTROLLER_GETVARIABLENAMES packet.
Definition: bcap_client.c:742
_BCAP_EXP_CLIENT HRESULT bCap_TaskGetVariable(int fd, uint32_t hTask, BSTR bstrName, BSTR bstrOption, uint32_t *hVariable)
Send the b-CAP ID_TASK_GETVARIABLE packet.
Definition: bcap_client.c:1318
_BCAP_EXP_CLIENT HRESULT bCap_TaskGetFileName(int fd, uint32_t hTask, BSTR *pVal)
Send the b-CAP ID_TASK_GETFILENAME packet.
Definition: bcap_client.c:1368
_BCAP_EXP_CLIENT HRESULT bCap_ExtensionPutTag(int fd, uint32_t hExtension, VARIANT newVal)
Send the b-CAP ID_EXTENSION_PUTTAG packet.
Definition: bcap_client.c:891
A type definition for the multi type variable.
Definition: dn_common.h:306
_BCAP_EXP_CLIENT HRESULT bCap_GetTimeout(int fd, uint32_t *timeout)
Gets timeout.
Definition: bcap_client.c:517
_BCAP_EXP_CLIENT HRESULT bCap_FilePutTag(int fd, uint32_t hFile, VARIANT newVal)
Send the b-CAP ID_FILE_PUTTAG packet.
Definition: bcap_client.c:1093
_BCAP_EXP_CLIENT HRESULT bCap_TaskStop(int fd, uint32_t hTask, int32_t lMode, BSTR bstrOption)
Send the b-CAP ID_TASK_STOP packet.
Definition: bcap_client.c:1354
_BCAP_EXP_CLIENT HRESULT bCap_ExtensionGetTag(int fd, uint32_t hExtension, VARIANT *pVal)
Send the b-CAP ID_EXTENSION_GETTAG packet.
Definition: bcap_client.c:884
_BCAP_EXP_CLIENT HRESULT bCap_FilePutValue(int fd, uint32_t hFile, VARIANT newVal)
Send the b-CAP ID_FILE_PUTVALUE packet.
Definition: bcap_client.c:1058
_BCAP_EXP_CLIENT HRESULT bCap_ControllerGetExtension(int fd, uint32_t hController, BSTR bstrName, BSTR bstrOption, uint32_t *hExtension)
Send the b-CAP ID_CONTROLLER_GETEXTENSION packet.
Definition: bcap_client.c:640
_BCAP_EXP_CLIENT HRESULT bCap_FileGetDateCreated(int fd, uint32_t hFile, VARIANT *pVal)
Send the b-CAP ID_FILE_GETDATECREATED packet.
Definition: bcap_client.c:1007
_BCAP_EXP_CLIENT HRESULT bCap_CommandPutTag(int fd, uint32_t hCommand, VARIANT newVal)
Send the b-CAP ID_COMMAND_PUTTAG packet.
Definition: bcap_client.c:1625
int int32_t
Definition: stdint.h:42
_BCAP_EXP_CLIENT HRESULT bCap_FileGetSize(int fd, uint32_t hFile, int32_t *pVal)
Send the b-CAP ID_FILE_GETSIZE packet.
Definition: bcap_client.c:1037
_BCAP_EXP_CLIENT HRESULT bCap_RobotGetID(int fd, uint32_t hRobot, VARIANT *pVal)
Send the b-CAP ID_ROBOT_GETID packet.
Definition: bcap_client.c:1287
_BCAP_EXP_CLIENT HRESULT bCap_FileGetValue(int fd, uint32_t hFile, VARIANT *pVal)
Send the b-CAP ID_FILE_GETVALUE packet.
Definition: bcap_client.c:1051
_BCAP_EXP_CLIENT HRESULT bCap_RobotSpeed(int fd, uint32_t hRobot, int32_t lAxis, float fSpeed)
Send the b-CAP ID_ROBOT_SPEED packet.
Definition: bcap_client.c:1231
_BCAP_EXP_CLIENT HRESULT bCap_ControllerGetVariable(int fd, uint32_t hController, BSTR bstrName, BSTR bstrOption, uint32_t *hVariable)
Send the b-CAP ID_CONTROLLER_GETVARIABLE packet.
Definition: bcap_client.c:684
_BCAP_EXP_CLIENT HRESULT bCap_FileGetType(int fd, uint32_t hFile, BSTR *pVal)
Send the b-CAP ID_FILE_GETTYPE packet.
Definition: bcap_client.c:1044
_BCAP_EXP_CLIENT HRESULT bCap_FilePutID(int fd, uint32_t hFile, VARIANT newVal)
Send the b-CAP ID_FILE_PUTID packet.
Definition: bcap_client.c:1107
_BCAP_EXP_CLIENT HRESULT bCap_SetTimeout(int fd, uint32_t timeout)
Sets timeout.
Definition: bcap_client.c:486
_BCAP_EXP_CLIENT HRESULT bCap_ControllerGetHelp(int fd, uint32_t hController, BSTR *pVal)
Send the b-CAP ID_CONTROLLER_GETHELP packet.
Definition: bcap_client.c:787
_BCAP_EXP_CLIENT HRESULT bCap_MessageGetDestination(int fd, uint32_t hMessage, BSTR *pVal)
Send the b-CAP ID_MESSAGE_GETDESTINATION packet.
Definition: bcap_client.c:1692
_BCAP_EXP_CLIENT HRESULT bCap_ExtensionGetID(int fd, uint32_t hExtension, VARIANT *pVal)
Send the b-CAP ID_EXTENSION_GETID packet.
Definition: bcap_client.c:898
_BCAP_EXP_CLIENT HRESULT bCap_VariableGetMicrosecond(int fd, uint32_t hVariable, int32_t *pVal)
Send the b-CAP ID_VARIABLE_GETMICROSECOND packet.
Definition: bcap_client.c:1513
_BCAP_EXP_CLIENT HRESULT bCap_CommandCancel(int fd, uint32_t hCommand)
Send the b-CAP ID_COMMAND_CANCEL packet.
Definition: bcap_client.c:1546
_BCAP_EXP_CLIENT HRESULT bCap_CommandPutID(int fd, uint32_t hCommand, VARIANT newVal)
Send the b-CAP ID_COMMAND_PUTID packet.
Definition: bcap_client.c:1639
_BCAP_EXP_CLIENT HRESULT bCap_VariablePutTag(int fd, uint32_t hVariable, VARIANT newVal)
Send the b-CAP ID_VARIABLE_PUTTAG packet.
Definition: bcap_client.c:1492
unsigned int retry
Definition: bcap_client.c:69
_BCAP_EXP_CLIENT HRESULT bCap_VariablePutID(int fd, uint32_t hVariable, VARIANT newVal)
Send the b-CAP ID_VARIABLE_PUTID packet.
Definition: bcap_client.c:1506
_BCAP_EXP_CLIENT HRESULT bCap_TaskPutID(int fd, uint32_t hTask, VARIANT newVal)
Send the b-CAP ID_TASK_PUTID packet.
Definition: bcap_client.c:1417
_BCAP_EXP_CLIENT HRESULT bCap_RobotDrive(int fd, uint32_t hRobot, int32_t lNo, float fMov, BSTR bstrOption)
Send the b-CAP ID_ROBOT_DRIVE packet.
Definition: bcap_client.c:1183
_BCAP_EXP_CLIENT HRESULT bCap_MessageGetSource(int fd, uint32_t hMessage, BSTR *pVal)
Send the b-CAP ID_MESSAGE_GETSOURCE packet.
Definition: bcap_client.c:1715
_BCAP_EXP_CLIENT HRESULT bCap_RobotGetName(int fd, uint32_t hRobot, BSTR *pVal)
Send the b-CAP ID_ROBOT_GETNAME packet.
Definition: bcap_client.c:1266
_BCAP_EXP_CLIENT HRESULT bCap_TaskRelease(int fd, uint32_t *hTask)
Send the b-CAP ID_TASK_RELEASE packet.
Definition: bcap_client.c:1424
_BCAP_EXP_CLIENT HRESULT bCap_VariableGetHelp(int fd, uint32_t hVariable, BSTR *pVal)
Send the b-CAP ID_VARIABLE_GETHELP packet.
Definition: bcap_client.c:1471
static int connect(SOCKET s, const struct sockaddr *name, int namelen)
_BCAP_EXP_CLIENT HRESULT bCap_Close_Client(int *pfd)
Ends b-CAP communication.
Definition: bcap_client.c:447
_BCAP_EXP_CLIENT HRESULT bCap_CommandGetHelp(int fd, uint32_t hCommand, BSTR *pVal)
Send the b-CAP ID_COMMAND_GETHELP packet.
Definition: bcap_client.c:1604
_BCAP_EXP_CLIENT HRESULT bCap_ControllerPutTag(int fd, uint32_t hController, VARIANT newVal)
Send the b-CAP ID_CONTROLLER_PUTTAG packet.
Definition: bcap_client.c:810
_BCAP_EXP_CLIENT HRESULT bCap_TaskExecute(int fd, uint32_t hTask, BSTR bstrCommand, VARIANT vntParam, VARIANT *pVal)
Send the b-CAP ID_TASK_EXECUTE packet.
Definition: bcap_client.c:1338
_BCAP_EXP_CLIENT HRESULT bCap_FileGetTag(int fd, uint32_t hFile, VARIANT *pVal)
Send the b-CAP ID_FILE_GETTAG packet.
Definition: bcap_client.c:1086
_BCAP_EXP_CLIENT HRESULT bCap_FileGetID(int fd, uint32_t hFile, VARIANT *pVal)
Send the b-CAP ID_FILE_GETID packet.
Definition: bcap_client.c:1100
_BCAP_EXP_CLIENT HRESULT bCap_ControllerGetMessage(int fd, uint32_t hController, uint32_t *hMessage)
Send the b-CAP ID_CONTROLLER_GETMESSAGE packet.
Definition: bcap_client.c:769
_BCAP_EXP_CLIENT HRESULT bCap_ControllerGetAttribute(int fd, uint32_t hController, int32_t *pVal)
Send the b-CAP ID_CONTROLLER_GETATTRIBUTE packet.
Definition: bcap_client.c:779
_BCAP_EXP_CLIENT HRESULT bCap_GetRetry(int fd, unsigned int *retry)
Gets retry count.
Definition: bcap_client.c:581
_BCAP_EXP_CLIENT HRESULT bCap_VariableGetName(int fd, uint32_t hVariable, BSTR *pVal)
Send the b-CAP ID_VARIABLE_GETNAME packet.
Definition: bcap_client.c:1478
_BCAP_EXP_CLIENT HRESULT bCap_SetRetry(int fd, unsigned int retry)
Sets retry count.
Definition: bcap_client.c:536
_BCAP_EXP_CLIENT HRESULT bCap_VariablePutValue(int fd, uint32_t hVariable, VARIANT newVal)
Send the b-CAP ID_VARIABLE_PUTVALUE packet.
Definition: bcap_client.c:1456
_BCAP_EXP_CLIENT HRESULT bCap_MessageGetValue(int fd, uint32_t hMessage, VARIANT *pVal)
Send the b-CAP ID_MESSAGE_GETVALUE packet.
Definition: bcap_client.c:1722
_BCAP_EXP_CLIENT HRESULT bCap_ServiceStop(int fd)
Send the b-CAP ID_SERVICE_STOP packet.
Definition: bcap_client.c:605
_BCAP_EXP_CLIENT HRESULT bCap_TaskGetID(int fd, uint32_t hTask, VARIANT *pVal)
Send the b-CAP ID_TASK_GETID packet.
Definition: bcap_client.c:1410


bcap_core
Author(s): DENSO WAVE INCORPORATED
autogenerated on Mon Jun 10 2019 13:12:20