00001
00025 #include <stdarg.h>
00026 #include "stdint.h"
00027 #include <stdlib.h>
00028 #include <string.h>
00029
00030 #if defined(_USE_WIN_API)
00031 #include <winsock2.h>
00032 #pragma comment(lib, "wsock32.lib")
00033 #elif defined(_USE_LINUX_API)
00034 #include <arpa/inet.h>
00035 #include <termios.h>
00036 #else
00037 #include "dn_additional.h"
00038 #endif
00039
00040 #include "dn_common.h"
00041 #include "dn_device.h"
00042 #include "dn_tcp.h"
00043 #include "dn_udp.h"
00044 #include "dn_com.h"
00045 #include "dn_thread.h"
00046 #include "bcap_common.h"
00047 #include "bcap_funcid.h"
00048 #include "bcap_client.h"
00049
00054 #define _RETRY_MIN (1)
00055
00060 #define _RETRY_MAX (7)
00061
00066 struct CONN_BCAP_CLIENT
00067 {
00068 struct CONN_PARAM_COMMON device;
00069 unsigned int retry;
00070 uint16_t serial;
00071 MUTEX mutex;
00072 };
00073
00074 static struct CONN_BCAP_CLIENT m_conn_param[BCAP_CONN_MAX];
00075
00081 static int
00082 find_open_address()
00083 {
00084 int i, index = -1;
00085
00086 for (i = 0; i < BCAP_CONN_MAX; i++) {
00087 if (m_conn_param[i].device.sock == 0) {
00088 index = i;
00089 break;
00090 }
00091 }
00092
00093 return (index + 1);
00094 }
00095
00102 static struct CONN_BCAP_CLIENT*
00103 check_address(int index)
00104 {
00105 index--;
00106
00107 if (index < 0 || BCAP_CONN_MAX <= index) {
00108 return NULL;
00109 }
00110 else if (m_conn_param[index].device.sock == 0) {
00111 return NULL;
00112 }
00113
00114 return &m_conn_param[index];
00115 }
00116
00124 static HRESULT
00125 send_receive(int index, struct BCAP_PACKET *packet_send,
00126 struct BCAP_PACKET *packet_recv)
00127 {
00128 unsigned int retry_cnt;
00129 HRESULT hr;
00130 struct CONN_BCAP_CLIENT *bcap_param;
00131
00132 bcap_param = check_address(index);
00133 if (bcap_param == NULL)
00134 return E_HANDLE;
00135
00136
00137 hr = lock_mutex(&bcap_param->mutex, INFINITE);
00138 if (FAILED(hr))
00139 return hr;
00140
00141 packet_send->reserv =
00142 (bcap_param->device.type == CONN_TCP) ? 0 : bcap_param->serial;
00143 packet_recv->id = E_FAIL;
00144
00145 for (retry_cnt = 0; retry_cnt < bcap_param->retry; retry_cnt++) {
00146 packet_send->serial = bcap_param->serial++;
00147 if (bcap_param->serial == 0)
00148 bcap_param->serial = 1;
00149
00150 hr = bcap_send(&bcap_param->device, packet_send);
00151 if (FAILED(hr))
00152 goto exit_proc;
00153
00154 while (1) {
00155 packet_recv->argc = 1;
00156 hr = bcap_recv(&bcap_param->device, packet_recv, 1);
00157 if (FAILED(hr)) {
00158 goto retry_proc;
00159 } else {
00160 if ((packet_send->serial == packet_recv->serial)
00161 && (packet_recv->id != S_EXECUTING))
00162 {
00163 goto exit_proc;
00164 }
00165 }
00166 }
00167 retry_proc:
00168 ;
00169 }
00170
00171 exit_proc:
00172
00173 unlock_mutex(&bcap_param->mutex);
00174
00175
00176 if (SUCCEEDED(hr)) {
00177 hr = packet_recv->id;
00178 }
00179
00180 return hr;
00181 }
00182
00195 static HRESULT
00196 invoke_function(int fd, int32_t id, int argc, char *format, ...)
00197 {
00198 int i, len;
00199 int32_t vt;
00200 void *pRet;
00201 char *chArg, *chRet, *chTmp;
00202 VARIANT *vntArg = NULL, vntRet;
00203 va_list list;
00204 struct BCAP_PACKET packet_send, packet_recv;
00205 HRESULT hr = S_OK;
00206
00207 if (argc > 0) {
00208 vntArg = (VARIANT *) malloc(argc * sizeof(VARIANT));
00209 if (vntArg == NULL)
00210 return E_OUTOFMEMORY;
00211 }
00212
00213 for (i = 0; i < argc; i++) {
00214 VariantInit(&vntArg[i]);
00215 }
00216 VariantInit(&vntRet);
00217
00218
00219 chArg = format;
00220
00221
00222 chRet = strchr(format, ':');
00223 if (chRet != NULL) {
00224 *chRet = '\0';
00225 chRet++;
00226 }
00227
00228 va_start(list, format);
00229
00230
00231 i = 0;
00232 while ((*chArg) || (i < argc)) {
00233 len = 0;
00234
00235 chTmp = strchr(chArg, ',');
00236 if (chTmp != NULL) {
00237 *chTmp = '\0';
00238 len++;
00239 }
00240
00241 len += strlen(chArg);
00242
00243 vt = atoi(chArg);
00244
00245 switch (vt) {
00246 case VT_I4:
00247 vntArg[i].vt = VT_I4;
00248 vntArg[i].lVal = va_arg(list, int32_t);
00249 break;
00250 case VT_R4:
00251 vntArg[i].vt = VT_R4;
00252 vntArg[i].fltVal = (float) va_arg(list, double);
00253 break;
00254 case VT_BSTR:
00255 vntArg[i].vt = VT_BSTR;
00256 vntArg[i].bstrVal = va_arg(list, BSTR);
00257 break;
00258 case VT_VARIANT:
00259 vntArg[i] = va_arg(list, VARIANT);
00260 break;
00261 default:
00262 hr = E_INVALIDARG;
00263 goto exit_proc;
00264 }
00265
00266 i++;
00267 chArg += len;
00268 }
00269
00270
00271 packet_send.id = id;
00272 packet_send.argc = argc;
00273 packet_send.args = vntArg;
00274
00275
00276 packet_recv.argc = 1;
00277 packet_recv.args = &vntRet;
00278
00279 vt = 0;
00280 pRet = NULL;
00281 if (chRet != NULL) {
00282 vt = atoi(chRet);
00283 pRet = va_arg(list, void *);
00284
00285 if ((pRet != NULL) && (vt == VT_VARIANT)) {
00286 packet_recv.args = (VARIANT *) pRet;
00287 }
00288 }
00289
00290 hr = send_receive(fd, &packet_send, &packet_recv);
00291
00292 if (SUCCEEDED(hr)) {
00293 if ((pRet == NULL) || (vt != vntRet.vt)) {
00294 goto exit_proc;
00295 }
00296
00297 switch (vt) {
00298 case VT_I4:
00299 *(int32_t *) pRet = vntRet.lVal;
00300 break;
00301 case VT_BSTR:
00302 *(BSTR *) pRet = SysAllocString(vntRet.bstrVal);
00303 break;
00304 default:
00305 break;
00306 }
00307 }
00308
00309 exit_proc:
00310 va_end(list);
00311
00312 if (vntArg != NULL) {
00313 free(vntArg);
00314 }
00315
00316 VariantClear(&vntRet);
00317
00318 return hr;
00319 }
00320
00321 HRESULT
00322 bCap_Open_Client(const char* connect, uint32_t timeout, unsigned int retry,
00323 int* pfd)
00324 {
00325 int index, *sock;
00326 extern uint32_t tcp_conn_timeout;
00327 HRESULT hr;
00328 void *conn_param;
00329 struct CONN_PARAM_ETH eth_param =
00330 { inet_addr("127.0.0.1"), htons(5007), 0, 0 };
00331 struct CONN_PARAM_COM com_param =
00332 { 1, 38400, NOPARITY, 8, ONESTOPBIT, 0 };
00333 struct CONN_BCAP_CLIENT *bcap_param;
00334 struct CONN_PARAM_COMMON *device;
00335 struct sockaddr_in *paddr;
00336
00337 if (connect == NULL || pfd == NULL)
00338 return E_INVALIDARG;
00339
00340 index = find_open_address();
00341 if (index == 0)
00342 return E_MAX_OBJECT;
00343
00344 bcap_param = &m_conn_param[index - 1];
00345 device = &bcap_param->device;
00346
00347
00348 device->type = parse_conn_type(connect);
00349 switch (device->type) {
00350 case CONN_TCP:
00351 hr = parse_conn_param_ether(connect, ð_param);
00352 conn_param = ð_param;
00353 device->arg = NULL;
00354 device->dn_open = &tcp_open_client;
00355 device->dn_close = &tcp_close;
00356 device->dn_send = &tcp_send;
00357 device->dn_recv = &tcp_recv;
00358 device->dn_set_timeout = &tcp_set_timeout;
00359 tcp_conn_timeout = timeout;
00360 break;
00361 case CONN_UDP:
00362 hr = parse_conn_param_ether(connect, ð_param);
00363 conn_param = ð_param;
00364 paddr = (struct sockaddr_in *) malloc(sizeof(struct sockaddr_in));
00365 if (paddr == NULL) {
00366 hr = E_OUTOFMEMORY;
00367 break;
00368 }
00369 paddr->sin_addr.s_addr = eth_param.dst_addr;
00370 paddr->sin_port = eth_param.dst_port;
00371 paddr->sin_family = AF_INET;
00372 device->arg = (void *) paddr;
00373 device->dn_open = &udp_open;
00374 device->dn_close = &udp_close;
00375 device->dn_send = &udp_send;
00376 device->dn_recv = &udp_recv;
00377 device->dn_set_timeout = &udp_set_timeout;
00378 break;
00379 case CONN_COM:
00380 hr = parse_conn_param_serial(connect, &com_param);
00381 conn_param = &com_param;
00382 device->arg = NULL;
00383 device->dn_open = &com_open;
00384 device->dn_close = &com_close;
00385 device->dn_send = &com_send;
00386 device->dn_recv = &com_recv;
00387 device->dn_set_timeout = &com_set_timeout;
00388 break;
00389 default:
00390 hr = E_INVALIDARG;
00391 break;
00392 }
00393
00394 if (FAILED(hr)) {
00395 if (device->arg != NULL) {
00396 free(device->arg);
00397 device->arg = NULL;
00398 }
00399 memset(bcap_param, 0, sizeof(struct CONN_BCAP_CLIENT));
00400 return hr;
00401 }
00402
00403
00404 hr = initialize_mutex(&bcap_param->mutex);
00405 if (FAILED(hr)) {
00406 if (device->arg != NULL) {
00407 free(device->arg);
00408 device->arg = NULL;
00409 }
00410 return hr;
00411 }
00412
00413
00414 sock = &device->sock;
00415 hr = device->dn_open(conn_param, sock);
00416 if (FAILED(hr)) {
00417 release_mutex(&bcap_param->mutex);
00418 if (device->arg != NULL) {
00419 free(device->arg);
00420 device->arg = NULL;
00421 }
00422 memset(bcap_param, 0, sizeof(struct CONN_BCAP_CLIENT));
00423 return hr;
00424 }
00425
00426 hr = bCap_SetTimeout(index, timeout);
00427 if (FAILED(hr)) {
00428 bCap_Close_Client(&index);
00429 return hr;
00430 }
00431
00432 hr = bCap_SetRetry(index, retry);
00433 if (FAILED(hr)) {
00434 bCap_Close_Client(&index);
00435 return hr;
00436 }
00437
00438
00439 bcap_param->serial = 1;
00440
00441 *pfd = index;
00442
00443 return S_OK;
00444 }
00445
00446 HRESULT
00447 bCap_Close_Client(int *pfd)
00448 {
00449 int index, *sock;
00450 struct CONN_BCAP_CLIENT *bcap_param;
00451 struct CONN_PARAM_COMMON *device;
00452
00453 if (pfd == NULL)
00454 return E_HANDLE;
00455
00456 index = *pfd;
00457
00458 bcap_param = check_address(index);
00459 if (bcap_param == NULL)
00460 return E_HANDLE;
00461
00462 device = &bcap_param->device;
00463 sock = &device->sock;
00464
00465
00466 release_mutex(&bcap_param->mutex);
00467
00468
00469 device->dn_close(sock);
00470
00471
00472 if (device->arg != NULL) {
00473 free(device->arg);
00474 device->arg = NULL;
00475 }
00476
00477
00478 memset(bcap_param, 0, sizeof(struct CONN_BCAP_CLIENT));
00479
00480 *pfd = 0;
00481
00482 return S_OK;
00483 }
00484
00485 HRESULT
00486 bCap_SetTimeout(int fd, uint32_t timeout)
00487 {
00488 int *sock;
00489 HRESULT hr;
00490 struct CONN_BCAP_CLIENT *bcap_param;
00491 struct CONN_PARAM_COMMON *device;
00492
00493 bcap_param = check_address(fd);
00494 if (bcap_param == NULL)
00495 return E_HANDLE;
00496
00497 device = &bcap_param->device;
00498 sock = &device->sock;
00499
00500
00501 hr = lock_mutex(&bcap_param->mutex, INFINITE);
00502 if (FAILED(hr))
00503 return hr;
00504
00505 hr = device->dn_set_timeout(*sock, timeout);
00506 if (SUCCEEDED(hr)) {
00507 device->timeout = timeout;
00508 }
00509
00510
00511 unlock_mutex(&bcap_param->mutex);
00512
00513 return hr;
00514 }
00515
00516 HRESULT
00517 bCap_GetTimeout(int fd, uint32_t *timeout)
00518 {
00519 struct CONN_BCAP_CLIENT *bcap_param;
00520 struct CONN_PARAM_COMMON *device;
00521
00522 bcap_param = check_address(fd);
00523 if (bcap_param == NULL)
00524 return E_HANDLE;
00525
00526 if (timeout == NULL)
00527 return E_INVALIDARG;
00528
00529 device = &bcap_param->device;
00530 *timeout = device->timeout;
00531
00532 return S_OK;
00533 }
00534
00535 HRESULT
00536 bCap_SetRetry(int fd, unsigned int retry)
00537 {
00538 HRESULT hr;
00539 struct CONN_BCAP_CLIENT *bcap_param;
00540 struct CONN_PARAM_COMMON *device;
00541
00542 bcap_param = check_address(fd);
00543 if (bcap_param == NULL)
00544 return E_HANDLE;
00545
00546 device = &bcap_param->device;
00547
00548
00549 hr = lock_mutex(&bcap_param->mutex, INFINITE);
00550 if (FAILED(hr))
00551 return hr;
00552
00553 switch (device->type) {
00554 case CONN_TCP:
00555 bcap_param->retry = 1;
00556 break;
00557 case CONN_UDP:
00558 case CONN_COM:
00559 if (retry < _RETRY_MIN) {
00560 bcap_param->retry = _RETRY_MIN;
00561 }
00562 else if (_RETRY_MAX < retry) {
00563 bcap_param->retry = _RETRY_MAX;
00564 }
00565 else {
00566 bcap_param->retry = retry;
00567 }
00568 break;
00569 default:
00570 hr = E_HANDLE;
00571 break;
00572 }
00573
00574
00575 unlock_mutex(&bcap_param->mutex);
00576
00577 return hr;
00578 }
00579
00580 HRESULT
00581 bCap_GetRetry(int fd, unsigned int *retry)
00582 {
00583 struct CONN_BCAP_CLIENT *bcap_param;
00584
00585 bcap_param = check_address(fd);
00586 if (bcap_param == NULL)
00587 return E_HANDLE;
00588
00589 if (retry == NULL)
00590 return E_INVALIDARG;
00591
00592 *retry = bcap_param->retry;
00593
00594 return S_OK;
00595 }
00596
00597 HRESULT
00598 bCap_ServiceStart(int fd, BSTR bstrOption)
00599 {
00600 char format[] = "8";
00601 return invoke_function(fd, ID_SERVICE_START, 1, format, bstrOption);
00602 }
00603
00604 HRESULT
00605 bCap_ServiceStop(int fd)
00606 {
00607 char format[] = "";
00608 return invoke_function(fd, ID_SERVICE_STOP, 0, format);
00609 }
00610
00611 HRESULT
00612 bCap_ControllerConnect(int fd, BSTR bstrName, BSTR bstrProvider,
00613 BSTR bstrMachine, BSTR bstrOption, uint32_t *hController)
00614 {
00615 char format[] = "8,8,8,8:3";
00616 if (hController == NULL)
00617 return E_INVALIDARG;
00618 return invoke_function(fd, ID_CONTROLLER_CONNECT, 4, format, bstrName,
00619 bstrProvider, bstrMachine, bstrOption, hController);
00620 }
00621
00622 HRESULT
00623 bCap_ControllerDisconnect(int fd, uint32_t *hController)
00624 {
00625 char format[] = "3";
00626 HRESULT hr;
00627
00628 if (hController == NULL)
00629 return E_INVALIDARG;
00630
00631 hr = invoke_function(fd, ID_CONTROLLER_DISCONNECT, 1, format, *hController);
00632 if (SUCCEEDED(hr)) {
00633 *hController = 0;
00634 }
00635
00636 return hr;
00637 }
00638
00639 HRESULT
00640 bCap_ControllerGetExtension(int fd, uint32_t hController, BSTR bstrName,
00641 BSTR bstrOption, uint32_t *hExtension)
00642 {
00643 char format[] = "3,8,8:3";
00644 if (hExtension == NULL)
00645 return E_INVALIDARG;
00646 return invoke_function(fd, ID_CONTROLLER_GETEXTENSION, 3, format, hController,
00647 bstrName, bstrOption, hExtension);
00648 }
00649
00650 HRESULT
00651 bCap_ControllerGetFile(int fd, uint32_t hController, BSTR bstrName,
00652 BSTR bstrOption, uint32_t *hFile)
00653 {
00654 char format[] = "3,8,8:3";
00655 if (hFile == NULL)
00656 return E_INVALIDARG;
00657 return invoke_function(fd, ID_CONTROLLER_GETFILE, 3, format, hController,
00658 bstrName, bstrOption, hFile);
00659 }
00660
00661 HRESULT
00662 bCap_ControllerGetRobot(int fd, uint32_t hController, BSTR bstrName,
00663 BSTR bstrOption, uint32_t *hRobot)
00664 {
00665 char format[] = "3,8,8:3";
00666 if (hRobot == NULL)
00667 return E_INVALIDARG;
00668 return invoke_function(fd, ID_CONTROLLER_GETROBOT, 3, format, hController,
00669 bstrName, bstrOption, hRobot);
00670 }
00671
00672 HRESULT
00673 bCap_ControllerGetTask(int fd, uint32_t hController, BSTR bstrName,
00674 BSTR bstrOption, uint32_t *hTask)
00675 {
00676 char format[] = "3,8,8:3";
00677 if (hTask == NULL)
00678 return E_INVALIDARG;
00679 return invoke_function(fd, ID_CONTROLLER_GETTASK, 3, format, hController,
00680 bstrName, bstrOption, hTask);
00681 }
00682
00683 HRESULT
00684 bCap_ControllerGetVariable(int fd, uint32_t hController, BSTR bstrName,
00685 BSTR bstrOption, uint32_t *hVariable)
00686 {
00687 char format[] = "3,8,8:3";
00688 if (hVariable == NULL)
00689 return E_INVALIDARG;
00690 return invoke_function(fd, ID_CONTROLLER_GETVARIABLE, 3, format, hController,
00691 bstrName, bstrOption, hVariable);
00692 }
00693
00694 HRESULT
00695 bCap_ControllerGetCommand(int fd, uint32_t hController, BSTR bstrName,
00696 BSTR bstrOption, uint32_t *hCommand)
00697 {
00698 char format[] = "3,8,8:3";
00699 if (hCommand == NULL)
00700 return E_INVALIDARG;
00701 return invoke_function(fd, ID_CONTROLLER_GETCOMMAND, 3, format, hController,
00702 bstrName, bstrOption, hCommand);
00703 }
00704
00705 HRESULT
00706 bCap_ControllerGetExtensionNames(int fd, uint32_t hController, BSTR bstrOption,
00707 VARIANT *pVal)
00708 {
00709 char format[] = "3,8:12";
00710 return invoke_function(fd, ID_CONTROLLER_GETEXTENSIONNAMES, 2, format,
00711 hController, bstrOption, pVal);
00712 }
00713
00714 HRESULT
00715 bCap_ControllerGetFileNames(int fd, uint32_t hController, BSTR bstrOption,
00716 VARIANT *pVal)
00717 {
00718 char format[] = "3,8:12";
00719 return invoke_function(fd, ID_CONTROLLER_GETFILENAMES, 2, format, hController,
00720 bstrOption, pVal);
00721 }
00722
00723 HRESULT
00724 bCap_ControllerGetRobotNames(int fd, uint32_t hController, BSTR bstrOption,
00725 VARIANT *pVal)
00726 {
00727 char format[] = "3,8:12";
00728 return invoke_function(fd, ID_CONTROLLER_GETROBOTNAMES, 2, format,
00729 hController, bstrOption, pVal);
00730 }
00731
00732 HRESULT
00733 bCap_ControllerGetTaskNames(int fd, uint32_t hController, BSTR bstrOption,
00734 VARIANT *pVal)
00735 {
00736 char format[] = "3,8:12";
00737 return invoke_function(fd, ID_CONTROLLER_GETTASKNAMES, 2, format, hController,
00738 bstrOption, pVal);
00739 }
00740
00741 HRESULT
00742 bCap_ControllerGetVariableNames(int fd, uint32_t hController, BSTR bstrOption,
00743 VARIANT *pVal)
00744 {
00745 char format[] = "3,8:12";
00746 return invoke_function(fd, ID_CONTROLLER_GETVARIABLENAMES, 2, format,
00747 hController, bstrOption, pVal);
00748 }
00749
00750 HRESULT
00751 bCap_ControllerGetCommandNames(int fd, uint32_t hController, BSTR bstrOption,
00752 VARIANT *pVal)
00753 {
00754 char format[] = "3,8:12";
00755 return invoke_function(fd, ID_CONTROLLER_GETCOMMANDNAMES, 2, format,
00756 hController, bstrOption, pVal);
00757 }
00758
00759 HRESULT
00760 bCap_ControllerExecute(int fd, uint32_t hController, BSTR bstrCommand,
00761 VARIANT vntParam, VARIANT *pVal)
00762 {
00763 char format[] = "3,8,12:12";
00764 return invoke_function(fd, ID_CONTROLLER_EXECUTE, 3, format, hController,
00765 bstrCommand, vntParam, pVal);
00766 }
00767
00768 HRESULT
00769 bCap_ControllerGetMessage(int fd, uint32_t hController, uint32_t *hMessage)
00770 {
00771 char format[] = "3:3";
00772 if (hMessage == NULL)
00773 return E_INVALIDARG;
00774 return invoke_function(fd, ID_CONTROLLER_GETMESSAGE, 1, format, hController,
00775 hMessage);
00776 }
00777
00778 HRESULT
00779 bCap_ControllerGetAttribute(int fd, uint32_t hController, int32_t *pVal)
00780 {
00781 char format[] = "3:3";
00782 return invoke_function(fd, ID_CONTROLLER_GETATTRIBUTE, 1, format, hController,
00783 pVal);
00784 }
00785
00786 HRESULT
00787 bCap_ControllerGetHelp(int fd, uint32_t hController, BSTR *pVal)
00788 {
00789 char format[] = "3:8";
00790 return invoke_function(fd, ID_CONTROLLER_GETHELP, 1, format, hController,
00791 pVal);
00792 }
00793
00794 HRESULT
00795 bCap_ControllerGetName(int fd, uint32_t hController, BSTR *pVal)
00796 {
00797 char format[] = "3:8";
00798 return invoke_function(fd, ID_CONTROLLER_GETNAME, 1, format, hController,
00799 pVal);
00800 }
00801
00802 HRESULT
00803 bCap_ControllerGetTag(int fd, uint32_t hController, VARIANT *pVal)
00804 {
00805 char format[] = "3:12";
00806 return invoke_function(fd, ID_CONTROLLER_GETTAG, 1, format, hController, pVal);
00807 }
00808
00809 HRESULT
00810 bCap_ControllerPutTag(int fd, uint32_t hController, VARIANT newVal)
00811 {
00812 char format[] = "3,12";
00813 return invoke_function(fd, ID_CONTROLLER_PUTTAG, 2, format, hController,
00814 newVal);
00815 }
00816
00817 HRESULT
00818 bCap_ControllerGetID(int fd, uint32_t hController, VARIANT *pVal)
00819 {
00820 char format[] = "3:12";
00821 return invoke_function(fd, ID_CONTROLLER_GETID, 1, format, hController, pVal);
00822 }
00823
00824 HRESULT
00825 bCap_ControllerPutID(int fd, uint32_t hController, VARIANT newVal)
00826 {
00827 char format[] = "3,12";
00828 return invoke_function(fd, ID_CONTROLLER_PUTID, 2, format, hController,
00829 newVal);
00830 }
00831
00832 HRESULT
00833 bCap_ExtensionGetVariable(int fd, uint32_t hExtension, BSTR bstrName,
00834 BSTR bstrOption, uint32_t *hVariable)
00835 {
00836 char format[] = "3,8,8:3";
00837 if (hVariable == NULL)
00838 return E_INVALIDARG;
00839 return invoke_function(fd, ID_EXTENSION_GETVARIABLE, 3, format, hExtension,
00840 bstrName, bstrOption, hVariable);
00841 }
00842
00843 HRESULT
00844 bCap_ExtensionGetVariableNames(int fd, uint32_t hExtension, BSTR bstrOption,
00845 VARIANT *pVal)
00846 {
00847 char format[] = "3,8:12";
00848 return invoke_function(fd, ID_EXTENSION_GETVARIABLENAMES, 2, format,
00849 hExtension, bstrOption, pVal);
00850 }
00851
00852 HRESULT
00853 bCap_ExtensionExecute(int fd, uint32_t hExtension, BSTR bstrCommand,
00854 VARIANT vntParam, VARIANT *pVal)
00855 {
00856 char format[] = "3,8,12:12";
00857 return invoke_function(fd, ID_EXTENSION_EXECUTE, 3, format, hExtension,
00858 bstrCommand, vntParam, pVal);
00859 }
00860
00861 HRESULT
00862 bCap_ExtensionGetAttribute(int fd, uint32_t hExtension, int32_t *pVal)
00863 {
00864 char format[] = "3:3";
00865 return invoke_function(fd, ID_EXTENSION_GETATTRIBUTE, 1, format, hExtension,
00866 pVal);
00867 }
00868
00869 HRESULT
00870 bCap_ExtensionGetHelp(int fd, uint32_t hExtension, BSTR *pVal)
00871 {
00872 char format[] = "3:8";
00873 return invoke_function(fd, ID_EXTENSION_GETHELP, 1, format, hExtension, pVal);
00874 }
00875
00876 HRESULT
00877 bCap_ExtensionGetName(int fd, uint32_t hExtension, BSTR *pVal)
00878 {
00879 char format[] = "3:8";
00880 return invoke_function(fd, ID_EXTENSION_GETNAME, 1, format, hExtension, pVal);
00881 }
00882
00883 HRESULT
00884 bCap_ExtensionGetTag(int fd, uint32_t hExtension, VARIANT *pVal)
00885 {
00886 char format[] = "3:12";
00887 return invoke_function(fd, ID_EXTENSION_GETTAG, 1, format, hExtension, pVal);
00888 }
00889
00890 HRESULT
00891 bCap_ExtensionPutTag(int fd, uint32_t hExtension, VARIANT newVal)
00892 {
00893 char format[] = "3,12";
00894 return invoke_function(fd, ID_EXTENSION_PUTTAG, 2, format, hExtension, newVal);
00895 }
00896
00897 HRESULT
00898 bCap_ExtensionGetID(int fd, uint32_t hExtension, VARIANT *pVal)
00899 {
00900 char format[] = "3:12";
00901 return invoke_function(fd, ID_EXTENSION_GETID, 1, format, hExtension, pVal);
00902 }
00903
00904 HRESULT
00905 bCap_ExtensionPutID(int fd, uint32_t hExtension, VARIANT newVal)
00906 {
00907 char format[] = "3,12";
00908 return invoke_function(fd, ID_EXTENSION_PUTID, 2, format, hExtension, newVal);
00909 }
00910
00911 HRESULT
00912 bCap_ExtensionRelease(int fd, uint32_t *hExtension)
00913 {
00914 char format[] = "3";
00915 HRESULT hr;
00916
00917 if (hExtension == NULL)
00918 return E_INVALIDARG;
00919
00920 hr = invoke_function(fd, ID_EXTENSION_RELEASE, 1, format, *hExtension);
00921 if (SUCCEEDED(hr)) {
00922 *hExtension = 0;
00923 }
00924
00925 return hr;
00926 }
00927
00928 HRESULT
00929 bCap_FileGetFile(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption,
00930 uint32_t *hFile2)
00931 {
00932 char format[] = "3,8,8:3";
00933 if (hFile2 == NULL)
00934 return E_INVALIDARG;
00935 return invoke_function(fd, ID_FILE_GETFILE, 3, format, hFile, bstrName,
00936 bstrOption, hFile2);
00937 }
00938
00939 HRESULT
00940 bCap_FileGetVariable(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption,
00941 uint32_t *hVariable)
00942 {
00943 char format[] = "3,8,8:3";
00944 if (hVariable == NULL)
00945 return E_INVALIDARG;
00946 return invoke_function(fd, ID_FILE_GETVARIABLE, 3, format, hFile, bstrName,
00947 bstrOption, hVariable);
00948 }
00949
00950 HRESULT
00951 bCap_FileGetFileNames(int fd, uint32_t hFile, BSTR bstrOption, VARIANT *pVal)
00952 {
00953 char format[] = "3,8:12";
00954 return invoke_function(fd, ID_FILE_GETFILENAMES, 2, format, hFile, bstrOption,
00955 pVal);
00956 }
00957
00958 HRESULT
00959 bCap_FileGetVariableNames(int fd, uint32_t hFile, BSTR bstrOption,
00960 VARIANT *pVal)
00961 {
00962 char format[] = "3,8:12";
00963 return invoke_function(fd, ID_FILE_GETVARIABLENAMES, 2, format, hFile,
00964 bstrOption, pVal);
00965 }
00966
00967 HRESULT
00968 bCap_FileExecute(int fd, uint32_t hFile, BSTR bstrCommand, VARIANT vntParam,
00969 VARIANT *pVal)
00970 {
00971 char format[] = "3,8,12:12";
00972 return invoke_function(fd, ID_FILE_EXECUTE, 3, format, hFile, bstrCommand,
00973 vntParam, pVal);
00974 }
00975
00976 HRESULT
00977 bCap_FileCopy(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption)
00978 {
00979 char format[] = "3,8,8";
00980 return invoke_function(fd, ID_FILE_COPY, 3, format, hFile, bstrName,
00981 bstrOption);
00982 }
00983
00984 HRESULT
00985 bCap_FileDelete(int fd, uint32_t hFile, BSTR bstrOption)
00986 {
00987 char format[] = "3,8";
00988 return invoke_function(fd, ID_FILE_DELETE, 2, format, hFile, bstrOption);
00989 }
00990
00991 HRESULT
00992 bCap_FileMove(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption)
00993 {
00994 char format[] = "3,8,8";
00995 return invoke_function(fd, ID_FILE_MOVE, 3, format, hFile, bstrName,
00996 bstrOption);
00997 }
00998
00999 HRESULT
01000 bCap_FileRun(int fd, uint32_t hFile, BSTR bstrOption, BSTR *pVal)
01001 {
01002 char format[] = "3,8:8";
01003 return invoke_function(fd, ID_FILE_RUN, 2, format, hFile, bstrOption, pVal);
01004 }
01005
01006 HRESULT
01007 bCap_FileGetDateCreated(int fd, uint32_t hFile, VARIANT *pVal)
01008 {
01009 char format[] = "3:12";
01010 return invoke_function(fd, ID_FILE_GETDATECREATED, 1, format, hFile, pVal);
01011 }
01012
01013 HRESULT
01014 bCap_FileGetDateLastAccessed(int fd, uint32_t hFile, VARIANT *pVal)
01015 {
01016 char format[] = "3:12";
01017 return invoke_function(fd, ID_FILE_GETDATELASTACCESSED, 1, format, hFile,
01018 pVal);
01019 }
01020
01021 HRESULT
01022 bCap_FileGetDateLastModified(int fd, uint32_t hFile, VARIANT *pVal)
01023 {
01024 char format[] = "3:12";
01025 return invoke_function(fd, ID_FILE_GETDATELASTMODIFIED, 1, format, hFile,
01026 pVal);
01027 }
01028
01029 HRESULT
01030 bCap_FileGetPath(int fd, uint32_t hFile, BSTR *pVal)
01031 {
01032 char format[] = "3:8";
01033 return invoke_function(fd, ID_FILE_GETPATH, 1, format, hFile, pVal);
01034 }
01035
01036 HRESULT
01037 bCap_FileGetSize(int fd, uint32_t hFile, int32_t *pVal)
01038 {
01039 char format[] = "3:3";
01040 return invoke_function(fd, ID_FILE_GETSIZE, 1, format, hFile, pVal);
01041 }
01042
01043 HRESULT
01044 bCap_FileGetType(int fd, uint32_t hFile, BSTR *pVal)
01045 {
01046 char format[] = "3:8";
01047 return invoke_function(fd, ID_FILE_GETTYPE, 1, format, hFile, pVal);
01048 }
01049
01050 HRESULT
01051 bCap_FileGetValue(int fd, uint32_t hFile, VARIANT *pVal)
01052 {
01053 char format[] = "3:12";
01054 return invoke_function(fd, ID_FILE_GETVALUE, 1, format, hFile, pVal);
01055 }
01056
01057 HRESULT
01058 bCap_FilePutValue(int fd, uint32_t hFile, VARIANT newVal)
01059 {
01060 char format[] = "3,12";
01061 return invoke_function(fd, ID_FILE_PUTVALUE, 2, format, hFile, newVal);
01062 }
01063
01064 HRESULT
01065 bCap_FileGetAttribute(int fd, uint32_t hFile, int32_t *pVal)
01066 {
01067 char format[] = "3:3";
01068 return invoke_function(fd, ID_FILE_GETATTRIBUTE, 1, format, hFile, pVal);
01069 }
01070
01071 HRESULT
01072 bCap_FileGetHelp(int fd, uint32_t hFile, BSTR *pVal)
01073 {
01074 char format[] = "3:8";
01075 return invoke_function(fd, ID_FILE_GETHELP, 1, format, hFile, pVal);
01076 }
01077
01078 HRESULT
01079 bCap_FileGetName(int fd, uint32_t hFile, BSTR *pVal)
01080 {
01081 char format[] = "3:8";
01082 return invoke_function(fd, ID_FILE_GETNAME, 1, format, hFile, pVal);
01083 }
01084
01085 HRESULT
01086 bCap_FileGetTag(int fd, uint32_t hFile, VARIANT *pVal)
01087 {
01088 char format[] = "3:12";
01089 return invoke_function(fd, ID_FILE_GETTAG, 1, format, hFile, pVal);
01090 }
01091
01092 HRESULT
01093 bCap_FilePutTag(int fd, uint32_t hFile, VARIANT newVal)
01094 {
01095 char format[] = "3,12";
01096 return invoke_function(fd, ID_FILE_PUTTAG, 2, format, hFile, newVal);
01097 }
01098
01099 HRESULT
01100 bCap_FileGetID(int fd, uint32_t hFile, VARIANT *pVal)
01101 {
01102 char format[] = "3:12";
01103 return invoke_function(fd, ID_FILE_GETID, 1, format, hFile, pVal);
01104 }
01105
01106 HRESULT
01107 bCap_FilePutID(int fd, uint32_t hFile, VARIANT newVal)
01108 {
01109 char format[] = "3,12";
01110 return invoke_function(fd, ID_FILE_PUTID, 2, format, hFile, newVal);
01111 }
01112
01113 HRESULT
01114 bCap_FileRelease(int fd, uint32_t *hFile)
01115 {
01116 char format[] = "3";
01117 HRESULT hr;
01118
01119 if (hFile == NULL)
01120 return E_INVALIDARG;
01121
01122 hr = invoke_function(fd, ID_FILE_RELEASE, 1, format, *hFile);
01123 if (SUCCEEDED(hr)) {
01124 *hFile = 0;
01125 }
01126
01127 return hr;
01128 }
01129
01130 HRESULT
01131 bCap_RobotGetVariable(int fd, uint32_t hRobot, BSTR bstrName, BSTR bstrOption,
01132 uint32_t *hVariable)
01133 {
01134 char format[] = "3,8,8:3";
01135 if (hVariable == NULL)
01136 return E_INVALIDARG;
01137 return invoke_function(fd, ID_ROBOT_GETVARIABLE, 3, format, hRobot, bstrName,
01138 bstrOption, hVariable);
01139 }
01140
01141 HRESULT
01142 bCap_RobotGetVariableNames(int fd, uint32_t hRobot, BSTR bstrOption,
01143 VARIANT *pVal)
01144 {
01145 char format[] = "3,8:12";
01146 return invoke_function(fd, ID_ROBOT_GETVARIABLENAMES, 2, format, hRobot,
01147 bstrOption, pVal);
01148 }
01149
01150 HRESULT
01151 bCap_RobotExecute(int fd, uint32_t hRobot, BSTR bstrCommand, VARIANT vntParam,
01152 VARIANT *pVal)
01153 {
01154 char format[] = "3,8,12:12";
01155 return invoke_function(fd, ID_ROBOT_EXECUTE, 3, format, hRobot, bstrCommand,
01156 vntParam, pVal);
01157 }
01158
01159 HRESULT
01160 bCap_RobotAccelerate(int fd, uint32_t hRobot, int32_t lAxis, float fAccel,
01161 float fDecel)
01162 {
01163 char format[] = "3,3,4,4";
01164 return invoke_function(fd, ID_ROBOT_ACCELERATE, 4, format, hRobot, lAxis,
01165 fAccel, fDecel);
01166 }
01167
01168 HRESULT
01169 bCap_RobotChange(int fd, uint32_t hRobot, BSTR bstrName)
01170 {
01171 char format[] = "3,8";
01172 return invoke_function(fd, ID_ROBOT_CHANGE, 2, format, hRobot, bstrName);
01173 }
01174
01175 HRESULT
01176 bCap_RobotChuck(int fd, uint32_t hRobot, BSTR bstrOption)
01177 {
01178 char format[] = "3,8";
01179 return invoke_function(fd, ID_ROBOT_CHUCK, 2, format, hRobot, bstrOption);
01180 }
01181
01182 HRESULT
01183 bCap_RobotDrive(int fd, uint32_t hRobot, int32_t lNo, float fMov,
01184 BSTR bstrOption)
01185 {
01186 char format[] = "3,3,4,8";
01187 return invoke_function(fd, ID_ROBOT_DRIVE, 4, format, hRobot, lNo, fMov,
01188 bstrOption);
01189 }
01190
01191 HRESULT
01192 bCap_RobotGoHome(int fd, uint32_t hRobot)
01193 {
01194 char format[] = "3";
01195 return invoke_function(fd, ID_ROBOT_GOHOME, 1, format, hRobot);
01196 }
01197
01198 HRESULT
01199 bCap_RobotHalt(int fd, uint32_t hRobot, BSTR bstrOption)
01200 {
01201 char format[] = "3,8";
01202 return invoke_function(fd, ID_ROBOT_HALT, 2, format, hRobot, bstrOption);
01203 }
01204
01205 HRESULT
01206 bCap_RobotHold(int fd, uint32_t hRobot, BSTR bstrOption)
01207 {
01208 char format[] = "3,8";
01209 return invoke_function(fd, ID_ROBOT_HOLD, 2, format, hRobot, bstrOption);
01210 }
01211
01212 HRESULT
01213 bCap_RobotMove(int fd, uint32_t hRobot, int32_t lComp, VARIANT vntPose,
01214 BSTR bstrOption)
01215 {
01216 char format[] = "3,3,12,8";
01217 return invoke_function(fd, ID_ROBOT_MOVE, 4, format, hRobot, lComp, vntPose,
01218 bstrOption);
01219 }
01220
01221 HRESULT
01222 bCap_RobotRotate(int fd, uint32_t hRobot, VARIANT vntRotSuf, float fDeg,
01223 VARIANT vntPivot, BSTR bstrOption)
01224 {
01225 char format[] = "3,12,4,12,8";
01226 return invoke_function(fd, ID_ROBOT_ROTATE, 5, format, hRobot, vntRotSuf,
01227 fDeg, vntPivot, bstrOption);
01228 }
01229
01230 HRESULT
01231 bCap_RobotSpeed(int fd, uint32_t hRobot, int32_t lAxis, float fSpeed)
01232 {
01233 char format[] = "3,3,4";
01234 return invoke_function(fd, ID_ROBOT_SPEED, 3, format, hRobot, lAxis, fSpeed);
01235 }
01236
01237 HRESULT
01238 bCap_RobotUnchuck(int fd, uint32_t hRobot, BSTR bstrOption)
01239 {
01240 char format[] = "3,8";
01241 return invoke_function(fd, ID_ROBOT_UNCHUCK, 2, format, hRobot, bstrOption);
01242 }
01243
01244 HRESULT
01245 bCap_RobotUnhold(int fd, uint32_t hRobot, BSTR bstrOption)
01246 {
01247 char format[] = "3,8";
01248 return invoke_function(fd, ID_ROBOT_UNHOLD, 2, format, hRobot, bstrOption);
01249 }
01250
01251 HRESULT
01252 bCap_RobotGetAttribute(int fd, uint32_t hRobot, int32_t *pVal)
01253 {
01254 char format[] = "3:3";
01255 return invoke_function(fd, ID_ROBOT_GETATTRIBUTE, 1, format, hRobot, pVal);
01256 }
01257
01258 HRESULT
01259 bCap_RobotGetHelp(int fd, uint32_t hRobot, BSTR *pVal)
01260 {
01261 char format[] = "3:8";
01262 return invoke_function(fd, ID_ROBOT_GETHELP, 1, format, hRobot, pVal);
01263 }
01264
01265 HRESULT
01266 bCap_RobotGetName(int fd, uint32_t hRobot, BSTR *pVal)
01267 {
01268 char format[] = "3:8";
01269 return invoke_function(fd, ID_ROBOT_GETNAME, 1, format, hRobot, pVal);
01270 }
01271
01272 HRESULT
01273 bCap_RobotGetTag(int fd, uint32_t hRobot, VARIANT *pVal)
01274 {
01275 char format[] = "3:12";
01276 return invoke_function(fd, ID_ROBOT_GETTAG, 1, format, hRobot, pVal);
01277 }
01278
01279 HRESULT
01280 bCap_RobotPutTag(int fd, uint32_t hRobot, VARIANT newVal)
01281 {
01282 char format[] = "3,12";
01283 return invoke_function(fd, ID_ROBOT_PUTTAG, 2, format, hRobot, newVal);
01284 }
01285
01286 HRESULT
01287 bCap_RobotGetID(int fd, uint32_t hRobot, VARIANT *pVal)
01288 {
01289 char format[] = "3:12";
01290 return invoke_function(fd, ID_ROBOT_GETID, 1, format, hRobot, pVal);
01291 }
01292
01293 HRESULT
01294 bCap_RobotPutID(int fd, uint32_t hRobot, VARIANT newVal)
01295 {
01296 char format[] = "3,12";
01297 return invoke_function(fd, ID_ROBOT_PUTID, 2, format, hRobot, newVal);
01298 }
01299
01300 HRESULT
01301 bCap_RobotRelease(int fd, uint32_t *hRobot)
01302 {
01303 char format[] = "3";
01304 HRESULT hr;
01305
01306 if (hRobot == NULL)
01307 return E_INVALIDARG;
01308
01309 hr = invoke_function(fd, ID_ROBOT_RELEASE, 1, format, *hRobot);
01310 if (SUCCEEDED(hr)) {
01311 *hRobot = 0;
01312 }
01313
01314 return hr;
01315 }
01316
01317 HRESULT
01318 bCap_TaskGetVariable(int fd, uint32_t hTask, BSTR bstrName, BSTR bstrOption,
01319 uint32_t *hVariable)
01320 {
01321 char format[] = "3,8,8:3";
01322 if (hVariable == NULL)
01323 return E_INVALIDARG;
01324 return invoke_function(fd, ID_TASK_GETVARIABLE, 3, format, hTask, bstrName,
01325 bstrOption, hVariable);
01326 }
01327
01328 HRESULT
01329 bCap_TaskGetVariableNames(int fd, uint32_t hTask, BSTR bstrOption,
01330 VARIANT *pVal)
01331 {
01332 char format[] = "3,8:12";
01333 return invoke_function(fd, ID_TASK_GETVARIABLENAMES, 2, format, hTask,
01334 bstrOption, pVal);
01335 }
01336
01337 HRESULT
01338 bCap_TaskExecute(int fd, uint32_t hTask, BSTR bstrCommand, VARIANT vntParam,
01339 VARIANT *pVal)
01340 {
01341 char format[] = "3,8,12:12";
01342 return invoke_function(fd, ID_TASK_EXECUTE, 3, format, hTask, bstrCommand,
01343 vntParam, pVal);
01344 }
01345
01346 HRESULT
01347 bCap_TaskStart(int fd, uint32_t hTask, int32_t lMode, BSTR bstrOption)
01348 {
01349 char format[] = "3,3,8";
01350 return invoke_function(fd, ID_TASK_START, 3, format, hTask, lMode, bstrOption);
01351 }
01352
01353 HRESULT
01354 bCap_TaskStop(int fd, uint32_t hTask, int32_t lMode, BSTR bstrOption)
01355 {
01356 char format[] = "3,3,8";
01357 return invoke_function(fd, ID_TASK_STOP, 3, format, hTask, lMode, bstrOption);
01358 }
01359
01360 HRESULT
01361 bCap_TaskDelete(int fd, uint32_t hTask, BSTR bstrOption)
01362 {
01363 char format[] = "3,8";
01364 return invoke_function(fd, ID_TASK_DELETE, 2, format, hTask, bstrOption);
01365 }
01366
01367 HRESULT
01368 bCap_TaskGetFileName(int fd, uint32_t hTask, BSTR *pVal)
01369 {
01370 char format[] = "3:8";
01371 return invoke_function(fd, ID_TASK_GETFILENAME, 1, format, hTask, pVal);
01372 }
01373
01374 HRESULT
01375 bCap_TaskGetAttribute(int fd, uint32_t hTask, int32_t *pVal)
01376 {
01377 char format[] = "3:3";
01378 return invoke_function(fd, ID_TASK_GETATTRIBUTE, 1, format, hTask, pVal);
01379 }
01380
01381 HRESULT
01382 bCap_TaskGetHelp(int fd, uint32_t hTask, BSTR *pVal)
01383 {
01384 char format[] = "3:8";
01385 return invoke_function(fd, ID_TASK_GETHELP, 1, format, hTask, pVal);
01386 }
01387
01388 HRESULT
01389 bCap_TaskGetName(int fd, uint32_t hTask, BSTR *pVal)
01390 {
01391 char format[] = "3:8";
01392 return invoke_function(fd, ID_TASK_GETNAME, 1, format, hTask, pVal);
01393 }
01394
01395 HRESULT
01396 bCap_TaskGetTag(int fd, uint32_t hTask, VARIANT *pVal)
01397 {
01398 char format[] = "3:12";
01399 return invoke_function(fd, ID_TASK_GETTAG, 1, format, hTask, pVal);
01400 }
01401
01402 HRESULT
01403 bCap_TaskPutTag(int fd, uint32_t hTask, VARIANT newVal)
01404 {
01405 char format[] = "3,12";
01406 return invoke_function(fd, ID_TASK_PUTTAG, 2, format, hTask, newVal);
01407 }
01408
01409 HRESULT
01410 bCap_TaskGetID(int fd, uint32_t hTask, VARIANT *pVal)
01411 {
01412 char format[] = "3:12";
01413 return invoke_function(fd, ID_TASK_GETID, 1, format, hTask, pVal);
01414 }
01415
01416 HRESULT
01417 bCap_TaskPutID(int fd, uint32_t hTask, VARIANT newVal)
01418 {
01419 char format[] = "3,12";
01420 return invoke_function(fd, ID_TASK_PUTID, 2, format, hTask, newVal);
01421 }
01422
01423 HRESULT
01424 bCap_TaskRelease(int fd, uint32_t *hTask)
01425 {
01426 char format[] = "3";
01427 HRESULT hr;
01428
01429 if (hTask == NULL)
01430 return E_INVALIDARG;
01431
01432 hr = invoke_function(fd, ID_TASK_RELEASE, 1, format, *hTask);
01433 if (SUCCEEDED(hr)) {
01434 *hTask = 0;
01435 }
01436
01437 return hr;
01438 }
01439
01440 HRESULT
01441 bCap_VariableGetDateTime(int fd, uint32_t hVariable, VARIANT *pVal)
01442 {
01443 char format[] = "3:12";
01444 return invoke_function(fd, ID_VARIABLE_GETDATETIME, 1, format, hVariable,
01445 pVal);
01446 }
01447
01448 HRESULT
01449 bCap_VariableGetValue(int fd, uint32_t hVariable, VARIANT *pVal)
01450 {
01451 char format[] = "3:12";
01452 return invoke_function(fd, ID_VARIABLE_GETVALUE, 1, format, hVariable, pVal);
01453 }
01454
01455 HRESULT
01456 bCap_VariablePutValue(int fd, uint32_t hVariable, VARIANT newVal)
01457 {
01458 char format[] = "3,12";
01459 return invoke_function(fd, ID_VARIABLE_PUTVALUE, 2, format, hVariable, newVal);
01460 }
01461
01462 HRESULT
01463 bCap_VariableGetAttribute(int fd, uint32_t hVariable, int32_t *pVal)
01464 {
01465 char format[] = "3:3";
01466 return invoke_function(fd, ID_VARIABLE_GETATTRIBUTE, 1, format, hVariable,
01467 pVal);
01468 }
01469
01470 HRESULT
01471 bCap_VariableGetHelp(int fd, uint32_t hVariable, BSTR *pVal)
01472 {
01473 char format[] = "3:8";
01474 return invoke_function(fd, ID_VARIABLE_GETHELP, 1, format, hVariable, pVal);
01475 }
01476
01477 HRESULT
01478 bCap_VariableGetName(int fd, uint32_t hVariable, BSTR *pVal)
01479 {
01480 char format[] = "3:8";
01481 return invoke_function(fd, ID_VARIABLE_GETNAME, 1, format, hVariable, pVal);
01482 }
01483
01484 HRESULT
01485 bCap_VariableGetTag(int fd, uint32_t hVariable, VARIANT *pVal)
01486 {
01487 char format[] = "3:12";
01488 return invoke_function(fd, ID_VARIABLE_GETTAG, 1, format, hVariable, pVal);
01489 }
01490
01491 HRESULT
01492 bCap_VariablePutTag(int fd, uint32_t hVariable, VARIANT newVal)
01493 {
01494 char format[] = "3,12";
01495 return invoke_function(fd, ID_VARIABLE_PUTTAG, 2, format, hVariable, newVal);
01496 }
01497
01498 HRESULT
01499 bCap_VariableGetID(int fd, uint32_t hVariable, VARIANT *pVal)
01500 {
01501 char format[] = "3:12";
01502 return invoke_function(fd, ID_VARIABLE_GETID, 1, format, hVariable, pVal);
01503 }
01504
01505 HRESULT
01506 bCap_VariablePutID(int fd, uint32_t hVariable, VARIANT newVal)
01507 {
01508 char format[] = "3,12";
01509 return invoke_function(fd, ID_VARIABLE_PUTID, 2, format, hVariable, newVal);
01510 }
01511
01512 HRESULT
01513 bCap_VariableGetMicrosecond(int fd, uint32_t hVariable, int32_t *pVal)
01514 {
01515 char format[] = "3:3";
01516 return invoke_function(fd, ID_VARIABLE_GETMICROSECOND, 1, format, hVariable,
01517 pVal);
01518 }
01519
01520 HRESULT
01521 bCap_VariableRelease(int fd, uint32_t *hVariable)
01522 {
01523 char format[] = "3";
01524 HRESULT hr;
01525
01526 if (hVariable == NULL)
01527 return E_INVALIDARG;
01528
01529 hr = invoke_function(fd, ID_VARIABLE_RELEASE, 1, format, *hVariable);
01530 if (SUCCEEDED(hr)) {
01531 *hVariable = 0;
01532 }
01533
01534 return hr;
01535 }
01536
01537 HRESULT
01538 bCap_CommandExecute(int fd, uint32_t hCommand, int32_t lMode, VARIANT *pVal)
01539 {
01540 char format[] = "3,3:12";
01541 return invoke_function(fd, ID_COMMAND_EXECUTE, 2, format, hCommand, lMode,
01542 pVal);
01543 }
01544
01545 HRESULT
01546 bCap_CommandCancel(int fd, uint32_t hCommand)
01547 {
01548 char format[] = "3";
01549 return invoke_function(fd, ID_COMMAND_CANCEL, 1, format, hCommand);
01550 }
01551
01552 HRESULT
01553 bCap_CommandGetTimeout(int fd, uint32_t hCommand, int32_t *pVal)
01554 {
01555 char format[] = "3:3";
01556 return invoke_function(fd, ID_COMMAND_GETTIMEOUT, 1, format, hCommand, pVal);
01557 }
01558
01559 HRESULT
01560 bCap_CommandPutTimeout(int fd, uint32_t hCommand, int32_t newVal)
01561 {
01562 char format[] = "3,3";
01563 return invoke_function(fd, ID_COMMAND_PUTTIMEOUT, 2, format, hCommand, newVal);
01564 }
01565
01566 HRESULT
01567 bCap_CommandGetState(int fd, uint32_t hCommand, int32_t *pVal)
01568 {
01569 char format[] = "3:3";
01570 return invoke_function(fd, ID_COMMAND_GETSTATE, 1, format, hCommand, pVal);
01571 }
01572
01573 HRESULT
01574 bCap_CommandGetParameters(int fd, uint32_t hCommand, VARIANT *pVal)
01575 {
01576 char format[] = "3:12";
01577 return invoke_function(fd, ID_COMMAND_GETPARAMETERS, 1, format, hCommand,
01578 pVal);
01579 }
01580
01581 HRESULT
01582 bCap_CommandPutParameters(int fd, uint32_t hCommand, VARIANT newVal)
01583 {
01584 char format[] = "3,12";
01585 return invoke_function(fd, ID_COMMAND_PUTPARAMETERS, 2, format, hCommand,
01586 newVal);
01587 }
01588
01589 HRESULT
01590 bCap_CommandGetResult(int fd, uint32_t hCommand, VARIANT *pVal)
01591 {
01592 char format[] = "3:12";
01593 return invoke_function(fd, ID_COMMAND_GETRESULT, 1, format, hCommand, pVal);
01594 }
01595
01596 HRESULT
01597 bCap_CommandGetAttribute(int fd, uint32_t hCommand, int32_t *pVal)
01598 {
01599 char format[] = "3:3";
01600 return invoke_function(fd, ID_COMMAND_GETATTRIBUTE, 1, format, hCommand, pVal);
01601 }
01602
01603 HRESULT
01604 bCap_CommandGetHelp(int fd, uint32_t hCommand, BSTR *pVal)
01605 {
01606 char format[] = "3:8";
01607 return invoke_function(fd, ID_COMMAND_GETHELP, 1, format, hCommand, pVal);
01608 }
01609
01610 HRESULT
01611 bCap_CommandGetName(int fd, uint32_t hCommand, BSTR *pVal)
01612 {
01613 char format[] = "3:8";
01614 return invoke_function(fd, ID_COMMAND_GETNAME, 1, format, hCommand, pVal);
01615 }
01616
01617 HRESULT
01618 bCap_CommandGetTag(int fd, uint32_t hCommand, VARIANT *pVal)
01619 {
01620 char format[] = "3:12";
01621 return invoke_function(fd, ID_COMMAND_GETTAG, 1, format, hCommand, pVal);
01622 }
01623
01624 HRESULT
01625 bCap_CommandPutTag(int fd, uint32_t hCommand, VARIANT newVal)
01626 {
01627 char format[] = "3,12";
01628 return invoke_function(fd, ID_COMMAND_PUTTAG, 2, format, hCommand, newVal);
01629 }
01630
01631 HRESULT
01632 bCap_CommandGetID(int fd, uint32_t hCommand, VARIANT *pVal)
01633 {
01634 char format[] = "3:12";
01635 return invoke_function(fd, ID_COMMAND_GETID, 1, format, hCommand, pVal);
01636 }
01637
01638 HRESULT
01639 bCap_CommandPutID(int fd, uint32_t hCommand, VARIANT newVal)
01640 {
01641 char format[] = "3,12";
01642 return invoke_function(fd, ID_COMMAND_PUTID, 2, format, hCommand, newVal);
01643 }
01644
01645 HRESULT
01646 bCap_CommandRelease(int fd, uint32_t *hCommand)
01647 {
01648 char format[] = "3";
01649 HRESULT hr;
01650
01651 if (hCommand == NULL)
01652 return E_INVALIDARG;
01653
01654 hr = invoke_function(fd, ID_COMMAND_RELEASE, 1, format, *hCommand);
01655 if (SUCCEEDED(hr)) {
01656 *hCommand = 0;
01657 }
01658
01659 return hr;
01660 }
01661
01662 HRESULT
01663 bCap_MessageReply(int fd, uint32_t hMessage, VARIANT vntData)
01664 {
01665 char format[] = "3,12";
01666 return invoke_function(fd, ID_MESSAGE_REPLY, 2, format, hMessage, vntData);
01667 }
01668
01669 HRESULT
01670 bCap_MessageClear(int fd, uint32_t hMessage)
01671 {
01672 char format[] = "3";
01673 return invoke_function(fd, ID_MESSAGE_CLEAR, 1, format, hMessage);
01674 }
01675
01676 HRESULT
01677 bCap_MessageGetDateTime(int fd, uint32_t hMessage, VARIANT *pVal)
01678 {
01679 char format[] = "3:12";
01680 return invoke_function(fd, ID_MESSAGE_GETDATETIME, 1, format, hMessage, pVal);
01681 }
01682
01683 HRESULT
01684 bCap_MessageGetDescription(int fd, uint32_t hMessage, BSTR *pVal)
01685 {
01686 char format[] = "3:8";
01687 return invoke_function(fd, ID_MESSAGE_GETDESCRIPTION, 1, format, hMessage,
01688 pVal);
01689 }
01690
01691 HRESULT
01692 bCap_MessageGetDestination(int fd, uint32_t hMessage, BSTR *pVal)
01693 {
01694 char format[] = "3:8";
01695 return invoke_function(fd, ID_MESSAGE_GETDESTINATION, 1, format, hMessage,
01696 pVal);
01697 }
01698
01699 HRESULT
01700 bCap_MessageGetNumber(int fd, uint32_t hMessage, int32_t *pVal)
01701 {
01702 char format[] = "3:3";
01703 return invoke_function(fd, ID_MESSAGE_GETNUMBER, 1, format, hMessage, pVal);
01704 }
01705
01706 HRESULT
01707 bCap_MessageGetSerialNumber(int fd, uint32_t hMessage, int32_t *pVal)
01708 {
01709 char format[] = "3:3";
01710 return invoke_function(fd, ID_MESSAGE_GETSERIALNUMBER, 1, format, hMessage,
01711 pVal);
01712 }
01713
01714 HRESULT
01715 bCap_MessageGetSource(int fd, uint32_t hMessage, BSTR *pVal)
01716 {
01717 char format[] = "3:8";
01718 return invoke_function(fd, ID_MESSAGE_GETSOURCE, 1, format, hMessage, pVal);
01719 }
01720
01721 HRESULT
01722 bCap_MessageGetValue(int fd, uint32_t hMessage, VARIANT *pVal)
01723 {
01724 char format[] = "3:12";
01725 return invoke_function(fd, ID_MESSAGE_GETVALUE, 1, format, hMessage, pVal);
01726 }
01727
01728 HRESULT
01729 bCap_MessageRelease(int fd, uint32_t *hMessage)
01730 {
01731 char format[] = "3";
01732 HRESULT hr;
01733
01734 if (hMessage == NULL)
01735 return E_INVALIDARG;
01736
01737 hr = invoke_function(fd, ID_MESSAGE_RELEASE, 1, format, *hMessage);
01738 if (SUCCEEDED(hr)) {
01739 *hMessage = 0;
01740 }
01741
01742 return hr;
01743 }