00001
00011
00012
00013
00014
00015
00016 #pragma pack(push,1) // for BCAP_VARIANT members alignment
00017 #ifdef __cplusplus
00018 extern "C"{
00019 #endif
00020
00021
00022 #ifndef B_CAP_H
00023 #define B_CAP_H
00024
00025
00026
00027
00028 #if WIN32
00029 #define SERIAL_BAUDRATE 115200
00030 #else
00031 #define SERIAL_BAUDRATE 0x0000f
00032 #endif
00033
00037 typedef enum BCAP_HRESULT {
00038
00039 BCAP_S_OK = 0 ,
00040 BCAP_E_NOTIMPL = 0x80004001,
00041 BCAP_E_ABORT = 0x80004004,
00042 BCAP_E_FAIL = 0x80004005,
00043 BCAP_E_UNEXPECTED = 0x8000FFFF,
00044 BCAP_E_INVALIDRCVPACKET = 0x80010001,
00045
00046
00047
00048 BCAP_E_INVALIDSNDPACKET = 0x80010002,
00049 BCAP_E_INVALIDARGTYPE = 0x80010003,
00050 BCAP_E_ROBOTISBUSY = 0x80010004,
00051 BCAP_E_INVALIDCOMMAND = 0x80010005,
00052
00053 BCAP_E_PACKETSIZEOVER = 0x80010011,
00054
00055 BCAP_E_ARGSIZEOVER = 0x80010012,
00056 BCAP_E_ACCESSDENIED = 0x80070005,
00057 BCAP_E_HANDLE = 0x80070006,
00058 BCAP_E_OUTOFMEMORY = 0x8007000E,
00059 BCAP_E_INVALIDARG = 0x80070057,
00060 BCAP_E_BUF_FULL = 0x83201483
00061
00062 } BCAP_HRESULT;
00063
00064
00065
00066
00067 #define VT_EMPTY 0
00068 #define VT_NULL 1
00069 #define VT_ERROR 10
00070 #define VT_UI1 17
00071 #define VT_I2 2
00072 #define VT_UI2 18
00073 #define VT_I4 3
00074 #define VT_UI4 19
00075 #define VT_R4 4
00076 #define VT_R8 5
00077 #define VT_CY 6
00078 #define VT_DATE 7
00079 #define VT_BOOL 11
00080 #define VT_BSTR 8
00081
00082 #define VT_VARIANT 12
00083 #define VT_ARRAY 0x2000
00084
00085
00086
00087 #ifndef SUCCEEDED
00088 #define SUCCEEDED(Status) ((int)(Status) >= 0)
00089 #endif
00090
00091 #ifndef FAILED
00092 #define FAILED(Status) ((int)(Status) < 0)
00093 #endif
00094
00095
00096 #ifndef u_char
00097 typedef unsigned char u_char;
00098 #endif
00099 #ifndef u_short
00100 typedef unsigned short u_short;
00101 #endif
00102 #ifndef u_int
00103 typedef unsigned int u_int;
00104 #endif
00105
00106
00107
00108 typedef struct {
00109 u_short Type;
00110 u_int Arrays;
00111 union {
00112 u_char CharValue;
00113 u_short ShortValue;
00114 u_int LongValue;
00115 float FloatValue;
00116 double DoubleValue;
00117
00118 u_char String[40 + 1];
00119 float FloatArray[16];
00120 double DoubleArray[16];
00121
00122
00123
00124 } Value;
00125 } BCAP_VARIANT;
00126
00127
00128 BCAP_HRESULT bCap_Open(const char *pIPStr, int iPort, int *piSockFd);
00129 BCAP_HRESULT bCap_Close(int iSockFd);
00130
00131 BCAP_HRESULT bCap_ServiceStart(int iSockFd);
00132 BCAP_HRESULT bCap_ServiceStop(int iSockFd);
00133
00134
00135 BCAP_HRESULT bCap_ControllerConnect(int iSockFd,char *pStrCtrlname, char *pStrProvName, char *pStrPcName, char *pStrOption, u_int *plhController);
00136 BCAP_HRESULT bCap_ControllerDisconnect(int iSockFd, u_int lhController);
00137
00138 BCAP_HRESULT bCap_ControllerGetRobot(int iSockFd, u_int lhController, char *pStrRobotName, char *pStrOption, u_int *lhRobot);
00139 BCAP_HRESULT bCap_ControllerGetVariable(int iSockFd, u_int lhController, char *pVarName, char *pstrOption, u_int *plhVar);
00140 BCAP_HRESULT bCap_ControllerGetTask(int iSockFd, u_int lhController, char *pTskName, char *pstrOption, u_int *plhVar);
00141 BCAP_HRESULT bCap_ControllerExecute(int iSockFd, u_int lhController, char *pStrCommand, char *pStrOption, void *plResult);
00142 BCAP_HRESULT bCap_ControllerExecute2(int iSockFd, u_int lhController, char *pStrCommand, BCAP_VARIANT *pVntOption, BCAP_VARIANT *pvntResult);
00143
00144
00145 BCAP_HRESULT bCap_RobotRelease(int iSockFd, u_int lhRobot);
00146 BCAP_HRESULT bCap_RobotGetVariable(int iSockFd, u_int lhRobot, char *pVarName, char *pStrOption, u_int *lhVarCurJnt);
00147 BCAP_HRESULT bCap_RobotExecute(int iSockFd, u_int lhRobot, char *pStrCommand, char *pStrOption, void *plResult);
00148 BCAP_HRESULT bCap_RobotChange(int iSockFd, u_int lhRobot, char *pStrCommand);
00149 BCAP_HRESULT bCap_RobotMove(int iSockFd, u_int lhRobot, long lComp, char *pStrPose, char *pStrOption);
00150 BCAP_HRESULT bCap_RobotExecuteSlaveMove(int iSockFd, u_int lhRobot, char *pStrCommand, float *pfOption, void *pResult);
00151 BCAP_HRESULT bCap_RobotExecute2(int iSockFd, u_int lhRobot, char *pStrCommand, BCAP_VARIANT *pVntOption, BCAP_VARIANT *pvntResult);
00152
00153
00154 BCAP_HRESULT bCap_TaskRelease(int iSockFd, u_int lhTask);
00155 BCAP_HRESULT bCap_TaskGetVariable(int iSockFd, u_int lhTask, char *pVarName, char *pstrOption, u_int *plhVar);
00156 BCAP_HRESULT bCap_TaskStart(int iSockFd, u_int lhTask, long lMode, char *pStrOption);
00157 BCAP_HRESULT bCap_TaskStop(int iSockFd, u_int lhTask, long lMode, char *pStrOption);
00158
00159
00160 BCAP_HRESULT bCap_VariableRelease(int iSockFd, u_int lhVar);
00161 BCAP_HRESULT bCap_VariableGetValue(int iSockFd, u_int lhVar, void *pVntValue);
00162 BCAP_HRESULT bCap_VariablePutValue(int iSockFd, u_int lhVar, u_short iType, u_int lArrays, void *pVntValue);
00163
00164 #endif
00165
00166 #ifdef __cplusplus
00167 }
00168 #endif
00169
00170 #pragma pack(pop)