bcap_client.h
Go to the documentation of this file.
00001 #ifndef BCAP_CLIENT_H_
00002 #define BCAP_CLIENT_H_
00003 
00036 #ifndef _BCAP_EXP_CLIENT
00037 #define _BCAP_EXP_CLIENT
00038 #endif /* _BCAP_EXP_CLIENT */
00039 
00040 #include "../dn_common.h"
00041 
00047 #define BCAP_CONN_MAX (20)
00048 
00049 #ifdef __cplusplus
00050 extern "C"
00051 {
00052 #endif
00053 
00062   _BCAP_EXP_CLIENT HRESULT
00063   bCap_Open_Client(const char *connect, uint32_t timeout, unsigned int retry,
00064       int *pfd);
00065 
00071   _BCAP_EXP_CLIENT HRESULT
00072   bCap_Close_Client(int *pfd);
00073 
00080   _BCAP_EXP_CLIENT HRESULT
00081   bCap_SetTimeout(int fd, uint32_t timeout);
00082 
00089   _BCAP_EXP_CLIENT HRESULT
00090   bCap_GetTimeout(int fd, uint32_t *timeout);
00091 
00098   _BCAP_EXP_CLIENT HRESULT
00099   bCap_SetRetry(int fd, unsigned int retry);
00100 
00107   _BCAP_EXP_CLIENT HRESULT
00108   bCap_GetRetry(int fd, unsigned int *retry);
00109 
00116   _BCAP_EXP_CLIENT HRESULT
00117   bCap_ServiceStart(int fd, BSTR bstrOption);
00118 
00124   _BCAP_EXP_CLIENT HRESULT
00125   bCap_ServiceStop(int fd);
00126 
00137   _BCAP_EXP_CLIENT HRESULT
00138   bCap_ControllerConnect(int fd, BSTR bstrName, BSTR bstrProvider,
00139       BSTR bstrMachine, BSTR bstrOption, uint32_t *hController);
00140 
00147   _BCAP_EXP_CLIENT HRESULT
00148   bCap_ControllerDisconnect(int fd, uint32_t *hController);
00149 
00159   _BCAP_EXP_CLIENT HRESULT
00160   bCap_ControllerGetExtension(int fd, uint32_t hController, BSTR bstrName,
00161       BSTR bstrOption, uint32_t *hExtension);
00162 
00172   _BCAP_EXP_CLIENT HRESULT
00173   bCap_ControllerGetFile(int fd, uint32_t hController, BSTR bstrName,
00174       BSTR bstrOption, uint32_t *hFile);
00175 
00185   _BCAP_EXP_CLIENT HRESULT
00186   bCap_ControllerGetRobot(int fd, uint32_t hController, BSTR bstrName,
00187       BSTR bstrOption, uint32_t *hRobot);
00188 
00198   _BCAP_EXP_CLIENT HRESULT
00199   bCap_ControllerGetTask(int fd, uint32_t hController, BSTR bstrName,
00200       BSTR bstrOption, uint32_t *hTask);
00201 
00211   _BCAP_EXP_CLIENT HRESULT
00212   bCap_ControllerGetVariable(int fd, uint32_t hController, BSTR bstrName,
00213       BSTR bstrOption, uint32_t *hVariable);
00214 
00224   _BCAP_EXP_CLIENT HRESULT
00225   bCap_ControllerGetCommand(int fd, uint32_t hController, BSTR bstrName,
00226       BSTR bstrOption, uint32_t *hCommand);
00227 
00236   _BCAP_EXP_CLIENT HRESULT
00237   bCap_ControllerGetExtensionNames(int fd, uint32_t hController,
00238       BSTR bstrOption, VARIANT *pVal);
00239 
00248   _BCAP_EXP_CLIENT HRESULT
00249   bCap_ControllerGetFileNames(int fd, uint32_t hController, BSTR bstrOption,
00250       VARIANT *pVal);
00251 
00260   _BCAP_EXP_CLIENT HRESULT
00261   bCap_ControllerGetRobotNames(int fd, uint32_t hController, BSTR bstrOption,
00262       VARIANT *pVal);
00263 
00272   _BCAP_EXP_CLIENT HRESULT
00273   bCap_ControllerGetTaskNames(int fd, uint32_t hController, BSTR bstrOption,
00274       VARIANT *pVal);
00275 
00284   _BCAP_EXP_CLIENT HRESULT
00285   bCap_ControllerGetVariableNames(int fd, uint32_t hController, BSTR bstrOption,
00286       VARIANT *pVal);
00287 
00296   _BCAP_EXP_CLIENT HRESULT
00297   bCap_ControllerGetCommandNames(int fd, uint32_t hController, BSTR bstrOption,
00298       VARIANT *pVal);
00299 
00309   _BCAP_EXP_CLIENT HRESULT
00310   bCap_ControllerExecute(int fd, uint32_t hController, BSTR bstrCommand,
00311       VARIANT vntParam, VARIANT *pVal);
00312 
00320   _BCAP_EXP_CLIENT HRESULT
00321   bCap_ControllerGetMessage(int fd, uint32_t hController, uint32_t *hMessage);
00322 
00330   _BCAP_EXP_CLIENT HRESULT
00331   bCap_ControllerGetAttribute(int fd, uint32_t hController, int32_t *pVal);
00332 
00340   _BCAP_EXP_CLIENT HRESULT
00341   bCap_ControllerGetHelp(int fd, uint32_t hController, BSTR *pVal);
00342 
00350   _BCAP_EXP_CLIENT HRESULT
00351   bCap_ControllerGetName(int fd, uint32_t hController, BSTR *pVal);
00352 
00360   _BCAP_EXP_CLIENT HRESULT
00361   bCap_ControllerGetTag(int fd, uint32_t hController, VARIANT *pVal);
00362 
00370   _BCAP_EXP_CLIENT HRESULT
00371   bCap_ControllerPutTag(int fd, uint32_t hController, VARIANT newVal);
00372 
00380   _BCAP_EXP_CLIENT HRESULT
00381   bCap_ControllerGetID(int fd, uint32_t hController, VARIANT *pVal);
00382 
00390   _BCAP_EXP_CLIENT HRESULT
00391   bCap_ControllerPutID(int fd, uint32_t hController, VARIANT newVal);
00392 
00402   _BCAP_EXP_CLIENT HRESULT
00403   bCap_ExtensionGetVariable(int fd, uint32_t hExtension, BSTR bstrName,
00404       BSTR bstrOption, uint32_t *hVariable);
00405 
00414   _BCAP_EXP_CLIENT HRESULT
00415   bCap_ExtensionGetVariableNames(int fd, uint32_t hExtension, BSTR bstrOption,
00416       VARIANT *pVal);
00417 
00427   _BCAP_EXP_CLIENT HRESULT
00428   bCap_ExtensionExecute(int fd, uint32_t hExtension, BSTR bstrCommand,
00429       VARIANT vntParam, VARIANT *pVal);
00430 
00438   _BCAP_EXP_CLIENT HRESULT
00439   bCap_ExtensionGetAttribute(int fd, uint32_t hExtension, int32_t *pVal);
00440 
00448   _BCAP_EXP_CLIENT HRESULT
00449   bCap_ExtensionGetHelp(int fd, uint32_t hExtension, BSTR *pVal);
00450 
00458   _BCAP_EXP_CLIENT HRESULT
00459   bCap_ExtensionGetName(int fd, uint32_t hExtension, BSTR *pVal);
00460 
00468   _BCAP_EXP_CLIENT HRESULT
00469   bCap_ExtensionGetTag(int fd, uint32_t hExtension, VARIANT *pVal);
00470 
00478   _BCAP_EXP_CLIENT HRESULT
00479   bCap_ExtensionPutTag(int fd, uint32_t hExtension, VARIANT newVal);
00480 
00488   _BCAP_EXP_CLIENT HRESULT
00489   bCap_ExtensionGetID(int fd, uint32_t hExtension, VARIANT *pVal);
00490 
00498   _BCAP_EXP_CLIENT HRESULT
00499   bCap_ExtensionPutID(int fd, uint32_t hExtension, VARIANT newVal);
00500 
00507   _BCAP_EXP_CLIENT HRESULT
00508   bCap_ExtensionRelease(int fd, uint32_t *hExtension);
00509 
00519   _BCAP_EXP_CLIENT HRESULT
00520   bCap_FileGetFile(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption,
00521       uint32_t *hFile2);
00522 
00532   _BCAP_EXP_CLIENT HRESULT
00533   bCap_FileGetVariable(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption,
00534       uint32_t *hVariable);
00535 
00544   _BCAP_EXP_CLIENT HRESULT
00545   bCap_FileGetFileNames(int fd, uint32_t hFile, BSTR bstrOption, VARIANT *pVal);
00546 
00555   _BCAP_EXP_CLIENT HRESULT
00556   bCap_FileGetVariableNames(int fd, uint32_t hFile, BSTR bstrOption,
00557       VARIANT *pVal);
00558 
00568   _BCAP_EXP_CLIENT HRESULT
00569   bCap_FileExecute(int fd, uint32_t hFile, BSTR bstrCommand, VARIANT vntParam,
00570       VARIANT *pVal);
00571 
00580   _BCAP_EXP_CLIENT HRESULT
00581   bCap_FileCopy(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption);
00582 
00590   _BCAP_EXP_CLIENT HRESULT
00591   bCap_FileDelete(int fd, uint32_t hFile, BSTR bstrOption);
00592 
00601   _BCAP_EXP_CLIENT HRESULT
00602   bCap_FileMove(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption);
00603 
00612   _BCAP_EXP_CLIENT HRESULT
00613   bCap_FileRun(int fd, uint32_t hFile, BSTR bstrOption, BSTR *pVal);
00614 
00622   _BCAP_EXP_CLIENT HRESULT
00623   bCap_FileGetDateCreated(int fd, uint32_t hFile, VARIANT *pVal);
00624 
00632   _BCAP_EXP_CLIENT HRESULT
00633   bCap_FileGetDateLastAccessed(int fd, uint32_t hFile, VARIANT *pVal);
00634 
00642   _BCAP_EXP_CLIENT HRESULT
00643   bCap_FileGetDateLastModified(int fd, uint32_t hFile, VARIANT *pVal);
00644 
00652   _BCAP_EXP_CLIENT HRESULT
00653   bCap_FileGetPath(int fd, uint32_t hFile, BSTR *pVal);
00654 
00662   _BCAP_EXP_CLIENT HRESULT
00663   bCap_FileGetSize(int fd, uint32_t hFile, int32_t *pVal);
00664 
00672   _BCAP_EXP_CLIENT HRESULT
00673   bCap_FileGetType(int fd, uint32_t hFile, BSTR *pVal);
00674 
00682   _BCAP_EXP_CLIENT HRESULT
00683   bCap_FileGetValue(int fd, uint32_t hFile, VARIANT *pVal);
00684 
00692   _BCAP_EXP_CLIENT HRESULT
00693   bCap_FilePutValue(int fd, uint32_t hFile, VARIANT newVal);
00694 
00702   _BCAP_EXP_CLIENT HRESULT
00703   bCap_FileGetAttribute(int fd, uint32_t hFile, int32_t *pVal);
00704 
00712   _BCAP_EXP_CLIENT HRESULT
00713   bCap_FileGetHelp(int fd, uint32_t hFile, BSTR *pVal);
00714 
00722   _BCAP_EXP_CLIENT HRESULT
00723   bCap_FileGetName(int fd, uint32_t hFile, BSTR *pVal);
00724 
00732   _BCAP_EXP_CLIENT HRESULT
00733   bCap_FileGetTag(int fd, uint32_t hFile, VARIANT *pVal);
00734 
00742   _BCAP_EXP_CLIENT HRESULT
00743   bCap_FilePutTag(int fd, uint32_t hFile, VARIANT newVal);
00744 
00752   _BCAP_EXP_CLIENT HRESULT
00753   bCap_FileGetID(int fd, uint32_t hFile, VARIANT *pVal);
00754 
00762   _BCAP_EXP_CLIENT HRESULT
00763   bCap_FilePutID(int fd, uint32_t hFile, VARIANT newVal);
00764 
00771   _BCAP_EXP_CLIENT HRESULT
00772   bCap_FileRelease(int fd, uint32_t *hFile);
00773 
00783   _BCAP_EXP_CLIENT HRESULT
00784   bCap_RobotGetVariable(int fd, uint32_t hRobot, BSTR bstrName, BSTR bstrOption,
00785       uint32_t *hVariable);
00786 
00795   _BCAP_EXP_CLIENT HRESULT
00796   bCap_RobotGetVariableNames(int fd, uint32_t hRobot, BSTR bstrOption,
00797       VARIANT *pVal);
00798 
00808   _BCAP_EXP_CLIENT HRESULT
00809   bCap_RobotExecute(int fd, uint32_t hRobot, BSTR bstrCommand, VARIANT vntParam,
00810       VARIANT *pVal);
00811 
00821   _BCAP_EXP_CLIENT HRESULT
00822   bCap_RobotAccelerate(int fd, uint32_t hRobot, int32_t lAxis, float fAccel,
00823       float fDecel);
00824 
00832   _BCAP_EXP_CLIENT HRESULT
00833   bCap_RobotChange(int fd, uint32_t hRobot, BSTR bstrName);
00834 
00842   _BCAP_EXP_CLIENT HRESULT
00843   bCap_RobotChuck(int fd, uint32_t hRobot, BSTR bstrOption);
00844 
00854   _BCAP_EXP_CLIENT HRESULT
00855   bCap_RobotDrive(int fd, uint32_t hRobot, int32_t lNo, float fMov,
00856       BSTR bstrOption);
00857 
00864   _BCAP_EXP_CLIENT HRESULT
00865   bCap_RobotGoHome(int fd, uint32_t hRobot);
00866 
00874   _BCAP_EXP_CLIENT HRESULT
00875   bCap_RobotHalt(int fd, uint32_t hRobot, BSTR bstrOption);
00876 
00884   _BCAP_EXP_CLIENT HRESULT
00885   bCap_RobotHold(int fd, uint32_t hRobot, BSTR bstrOption);
00886 
00896   _BCAP_EXP_CLIENT HRESULT
00897   bCap_RobotMove(int fd, uint32_t hRobot, int32_t lComp, VARIANT vntPose,
00898       BSTR bstrOption);
00899 
00910   _BCAP_EXP_CLIENT HRESULT
00911   bCap_RobotRotate(int fd, uint32_t hRobot, VARIANT vntRotSuf, float fDeg,
00912       VARIANT vntPivot, BSTR bstrOption);
00913 
00922   _BCAP_EXP_CLIENT HRESULT
00923   bCap_RobotSpeed(int fd, uint32_t hRobot, int32_t lAxis, float fSpeed);
00924 
00932   _BCAP_EXP_CLIENT HRESULT
00933   bCap_RobotUnchuck(int fd, uint32_t hRobot, BSTR bstrOption);
00934 
00942   _BCAP_EXP_CLIENT HRESULT
00943   bCap_RobotUnhold(int fd, uint32_t hRobot, BSTR bstrOption);
00944 
00952   _BCAP_EXP_CLIENT HRESULT
00953   bCap_RobotGetAttribute(int fd, uint32_t hRobot, int32_t *pVal);
00954 
00962   _BCAP_EXP_CLIENT HRESULT
00963   bCap_RobotGetHelp(int fd, uint32_t hRobot, BSTR *pVal);
00964 
00972   _BCAP_EXP_CLIENT HRESULT
00973   bCap_RobotGetName(int fd, uint32_t hRobot, BSTR *pVal);
00974 
00982   _BCAP_EXP_CLIENT HRESULT
00983   bCap_RobotGetTag(int fd, uint32_t hRobot, VARIANT *pVal);
00984 
00992   _BCAP_EXP_CLIENT HRESULT
00993   bCap_RobotPutTag(int fd, uint32_t hRobot, VARIANT newVal);
00994 
01002   _BCAP_EXP_CLIENT HRESULT
01003   bCap_RobotGetID(int fd, uint32_t hRobot, VARIANT *pVal);
01004 
01012   _BCAP_EXP_CLIENT HRESULT
01013   bCap_RobotPutID(int fd, uint32_t hRobot, VARIANT newVal);
01014 
01021   _BCAP_EXP_CLIENT HRESULT
01022   bCap_RobotRelease(int fd, uint32_t *hRobot);
01023 
01033   _BCAP_EXP_CLIENT HRESULT
01034   bCap_TaskGetVariable(int fd, uint32_t hTask, BSTR bstrName, BSTR bstrOption,
01035       uint32_t *hVariable);
01036 
01045   _BCAP_EXP_CLIENT HRESULT
01046   bCap_TaskGetVariableNames(int fd, uint32_t hTask, BSTR bstrOption,
01047       VARIANT *pVal);
01048 
01058   _BCAP_EXP_CLIENT HRESULT
01059   bCap_TaskExecute(int fd, uint32_t hTask, BSTR bstrCommand, VARIANT vntParam,
01060       VARIANT *pVal);
01061 
01070   _BCAP_EXP_CLIENT HRESULT
01071   bCap_TaskStart(int fd, uint32_t hTask, int32_t lMode, BSTR bstrOption);
01072 
01081   _BCAP_EXP_CLIENT HRESULT
01082   bCap_TaskStop(int fd, uint32_t hTask, int32_t lMode, BSTR bstrOption);
01083 
01091   _BCAP_EXP_CLIENT HRESULT
01092   bCap_TaskDelete(int fd, uint32_t hTask, BSTR bstrOption);
01093 
01101   _BCAP_EXP_CLIENT HRESULT
01102   bCap_TaskGetFileName(int fd, uint32_t hTask, BSTR *pVal);
01103 
01111   _BCAP_EXP_CLIENT HRESULT
01112   bCap_TaskGetAttribute(int fd, uint32_t hTask, int32_t *pVal);
01113 
01121   _BCAP_EXP_CLIENT HRESULT
01122   bCap_TaskGetHelp(int fd, uint32_t hTask, BSTR *pVal);
01123 
01131   _BCAP_EXP_CLIENT HRESULT
01132   bCap_TaskGetName(int fd, uint32_t hTask, BSTR *pVal);
01133 
01141   _BCAP_EXP_CLIENT HRESULT
01142   bCap_TaskGetTag(int fd, uint32_t hTask, VARIANT *pVal);
01143 
01151   _BCAP_EXP_CLIENT HRESULT
01152   bCap_TaskPutTag(int fd, uint32_t hTask, VARIANT newVal);
01153 
01161   _BCAP_EXP_CLIENT HRESULT
01162   bCap_TaskGetID(int fd, uint32_t hTask, VARIANT *pVal);
01163 
01171   _BCAP_EXP_CLIENT HRESULT
01172   bCap_TaskPutID(int fd, uint32_t hTask, VARIANT newVal);
01173 
01180   _BCAP_EXP_CLIENT HRESULT
01181   bCap_TaskRelease(int fd, uint32_t *hTask);
01182 
01190   _BCAP_EXP_CLIENT HRESULT
01191   bCap_VariableGetDateTime(int fd, uint32_t hVariable, VARIANT *pVal);
01192 
01200   _BCAP_EXP_CLIENT HRESULT
01201   bCap_VariableGetValue(int fd, uint32_t hVariable, VARIANT *pVal);
01202 
01210   _BCAP_EXP_CLIENT HRESULT
01211   bCap_VariablePutValue(int fd, uint32_t hVariable, VARIANT newVal);
01212 
01220   _BCAP_EXP_CLIENT HRESULT
01221   bCap_VariableGetAttribute(int fd, uint32_t hVariable, int32_t *pVal);
01222 
01230   _BCAP_EXP_CLIENT HRESULT
01231   bCap_VariableGetHelp(int fd, uint32_t hVariable, BSTR *pVal);
01232 
01240   _BCAP_EXP_CLIENT HRESULT
01241   bCap_VariableGetName(int fd, uint32_t hVariable, BSTR *pVal);
01242 
01250   _BCAP_EXP_CLIENT HRESULT
01251   bCap_VariableGetTag(int fd, uint32_t hVariable, VARIANT *pVal);
01252 
01260   _BCAP_EXP_CLIENT HRESULT
01261   bCap_VariablePutTag(int fd, uint32_t hVariable, VARIANT newVal);
01262 
01270   _BCAP_EXP_CLIENT HRESULT
01271   bCap_VariableGetID(int fd, uint32_t hVariable, VARIANT *pVal);
01272 
01280   _BCAP_EXP_CLIENT HRESULT
01281   bCap_VariablePutID(int fd, uint32_t hVariable, VARIANT newVal);
01282 
01290   _BCAP_EXP_CLIENT HRESULT
01291   bCap_VariableGetMicrosecond(int fd, uint32_t hVariable, int32_t *pVal);
01292 
01299   _BCAP_EXP_CLIENT HRESULT
01300   bCap_VariableRelease(int fd, uint32_t *hVariable);
01301 
01310   _BCAP_EXP_CLIENT HRESULT
01311   bCap_CommandExecute(int fd, uint32_t hCommand, int32_t lMode, VARIANT *pVal);
01312 
01319   _BCAP_EXP_CLIENT HRESULT
01320   bCap_CommandCancel(int fd, uint32_t hCommand);
01321 
01329   _BCAP_EXP_CLIENT HRESULT
01330   bCap_CommandGetTimeout(int fd, uint32_t hCommand, int32_t *pVal);
01331 
01339   _BCAP_EXP_CLIENT HRESULT
01340   bCap_CommandPutTimeout(int fd, uint32_t hCommand, int32_t newVal);
01341 
01349   _BCAP_EXP_CLIENT HRESULT
01350   bCap_CommandGetState(int fd, uint32_t hCommand, int32_t *pVal);
01351 
01359   _BCAP_EXP_CLIENT HRESULT
01360   bCap_CommandGetParameters(int fd, uint32_t hCommand, VARIANT *pVal);
01361 
01369   _BCAP_EXP_CLIENT HRESULT
01370   bCap_CommandPutParameters(int fd, uint32_t hCommand, VARIANT newVal);
01371 
01379   _BCAP_EXP_CLIENT HRESULT
01380   bCap_CommandGetResult(int fd, uint32_t hCommand, VARIANT *pVal);
01381 
01389   _BCAP_EXP_CLIENT HRESULT
01390   bCap_CommandGetAttribute(int fd, uint32_t hCommand, int32_t *pVal);
01391 
01399   _BCAP_EXP_CLIENT HRESULT
01400   bCap_CommandGetHelp(int fd, uint32_t hCommand, BSTR *pVal);
01401 
01409   _BCAP_EXP_CLIENT HRESULT
01410   bCap_CommandGetName(int fd, uint32_t hCommand, BSTR *pVal);
01411 
01419   _BCAP_EXP_CLIENT HRESULT
01420   bCap_CommandGetTag(int fd, uint32_t hCommand, VARIANT *pVal);
01421 
01429   _BCAP_EXP_CLIENT HRESULT
01430   bCap_CommandPutTag(int fd, uint32_t hCommand, VARIANT newVal);
01431 
01439   _BCAP_EXP_CLIENT HRESULT
01440   bCap_CommandGetID(int fd, uint32_t hCommand, VARIANT *pVal);
01441 
01449   _BCAP_EXP_CLIENT HRESULT
01450   bCap_CommandPutID(int fd, uint32_t hCommand, VARIANT newVal);
01451 
01458   _BCAP_EXP_CLIENT HRESULT
01459   bCap_CommandRelease(int fd, uint32_t *hCommand);
01460 
01468   _BCAP_EXP_CLIENT HRESULT
01469   bCap_MessageReply(int fd, uint32_t hMessage, VARIANT vntData);
01470 
01477   _BCAP_EXP_CLIENT HRESULT
01478   bCap_MessageClear(int fd, uint32_t hMessage);
01479 
01487   _BCAP_EXP_CLIENT HRESULT
01488   bCap_MessageGetDateTime(int fd, uint32_t hMessage, VARIANT *pVal);
01489 
01497   _BCAP_EXP_CLIENT HRESULT
01498   bCap_MessageGetDescription(int fd, uint32_t hMessage, BSTR *pVal);
01499 
01507   _BCAP_EXP_CLIENT HRESULT
01508   bCap_MessageGetDestination(int fd, uint32_t hMessage, BSTR *pVal);
01509 
01517   _BCAP_EXP_CLIENT HRESULT
01518   bCap_MessageGetNumber(int fd, uint32_t hMessage, int32_t *pVal);
01519 
01527   _BCAP_EXP_CLIENT HRESULT
01528   bCap_MessageGetSerialNumber(int fd, uint32_t hMessage, int32_t *pVal);
01529 
01537   _BCAP_EXP_CLIENT HRESULT
01538   bCap_MessageGetSource(int fd, uint32_t hMessage, BSTR *pVal);
01539 
01547   _BCAP_EXP_CLIENT HRESULT
01548   bCap_MessageGetValue(int fd, uint32_t hMessage, VARIANT *pVal);
01549 
01556   _BCAP_EXP_CLIENT HRESULT
01557   bCap_MessageRelease(int fd, uint32_t *hMessage);
01558 
01559 #ifdef __cplusplus
01560 }
01561 #endif
01562 
01563 #endif /* BCAP_CLIENT_H_ */


bcap_core
Author(s): DENSO WAVE INCORPORATED
autogenerated on Thu Jun 6 2019 21:00:02