bcap_client.c
Go to the documentation of this file.
1 
25 #include <stdarg.h>
26 #include "stdint.h"
27 #include <stdlib.h>
28 #include <string.h>
29 
30 #if defined(_USE_WIN_API)
31 #include <winsock2.h>
32 #pragma comment(lib, "wsock32.lib")
33 #elif defined(_USE_LINUX_API)
34 #include <arpa/inet.h>
35 #include <termios.h>
36 #else
37 #include "dn_additional.h"
38 #endif
39 
40 #include "dn_common.h"
41 #include "dn_device.h"
42 #include "dn_tcp.h"
43 #include "dn_udp.h"
44 #include "dn_com.h"
45 #include "dn_thread.h"
46 #include "bcap_common.h"
47 #include "bcap_funcid.h"
48 #include "bcap_client.h"
49 
54 #define _RETRY_MIN (1)
55 
60 #define _RETRY_MAX (7)
61 
67 {
68  struct CONN_PARAM_COMMON device; /* Common communication object */
69  unsigned int retry; /* Retry count: >= 0 */
70  uint16_t serial; /* Serial number: 1 - 65535 */
71  MUTEX mutex; /* Mutex object */
72 };
73 
75 
81 static int
83 {
84  int i, index = -1;
85 
86  for (i = 0; i < BCAP_CONN_MAX; i++) {
87  if (m_conn_param[i].device.sock == 0) {
88  index = i;
89  break;
90  }
91  }
92 
93  return (index + 1);
94 }
95 
102 static struct CONN_BCAP_CLIENT*
103 check_address(int index)
104 {
105  index--;
106 
107  if (index < 0 || BCAP_CONN_MAX <= index) {
108  return NULL;
109  }
110  else if (m_conn_param[index].device.sock == 0) {
111  return NULL;
112  }
113 
114  return &m_conn_param[index];
115 }
116 
124 static HRESULT
125 send_receive(int index, struct BCAP_PACKET *packet_send,
126  struct BCAP_PACKET *packet_recv)
127 {
128  unsigned int retry_cnt;
129  HRESULT hr;
130  struct CONN_BCAP_CLIENT *bcap_param;
131 
132  bcap_param = check_address(index);
133  if (bcap_param == NULL)
134  return E_HANDLE;
135 
136  /* Locks mutex and must not returns this function without end of one. */
137  hr = lock_mutex(&bcap_param->mutex, INFINITE);
138  if (FAILED(hr))
139  return hr;
140 
141  packet_send->reserv =
142  (bcap_param->device.type == CONN_TCP) ? 0 : bcap_param->serial;
143  packet_recv->id = E_FAIL;
144 
145  for (retry_cnt = 0; retry_cnt < bcap_param->retry; retry_cnt++) {
146  packet_send->serial = bcap_param->serial++;
147  if (bcap_param->serial == 0)
148  bcap_param->serial = 1;
149 
150  hr = bcap_send(&bcap_param->device, packet_send);
151  if (FAILED(hr))
152  goto exit_proc;
153 
154  while (1) {
155  packet_recv->argc = 1;
156  hr = bcap_recv(&bcap_param->device, packet_recv, 1);
157  if (FAILED(hr)) {
158  goto retry_proc;
159  } else {
160  if ((packet_send->serial == packet_recv->serial)
161  && (packet_recv->id != S_EXECUTING))
162  {
163  goto exit_proc;
164  }
165  }
166  }
167 retry_proc:
168  ;
169  }
170 
171 exit_proc:
172  /* Unlocks mutex */
173  unlock_mutex(&bcap_param->mutex);
174 
175  /* Sets the received return code to hr */
176  if (SUCCEEDED(hr)) {
177  hr = packet_recv->id;
178  }
179 
180  return hr;
181 }
182 
195 static HRESULT
196 invoke_function(int fd, int32_t id, int argc, char *format, ...)
197 {
198  int i, len;
199  int32_t vt;
200  void *pRet;
201  char *chArg, *chRet, *chTmp;
202  VARIANT *vntArg = NULL, vntRet;
203  va_list list;
204  struct BCAP_PACKET packet_send, packet_recv;
205  HRESULT hr = S_OK;
206 
207  if (argc > 0) {
208  vntArg = (VARIANT *) malloc(argc * sizeof(VARIANT));
209  if (vntArg == NULL)
210  return E_OUTOFMEMORY;
211  }
212 
213  for (i = 0; i < argc; i++) {
214  VariantInit(&vntArg[i]);
215  }
216  VariantInit(&vntRet);
217 
218  /* Input parameters */
219  chArg = format;
220 
221  /* Output parameter */
222  chRet = strchr(format, ':');
223  if (chRet != NULL) {
224  *chRet = '\0';
225  chRet++;
226  }
227 
228  va_start(list, format);
229 
230  /* Sets input parameters */
231  i = 0;
232  while ((*chArg) || (i < argc)) {
233  len = 0;
234 
235  chTmp = strchr(chArg, ',');
236  if (chTmp != NULL) {
237  *chTmp = '\0';
238  len++;
239  }
240 
241  len += strlen(chArg);
242 
243  vt = atoi(chArg);
244 
245  switch (vt) {
246  case VT_I4:
247  vntArg[i].vt = VT_I4;
248  vntArg[i].lVal = va_arg(list, int32_t);
249  break;
250  case VT_R4:
251  vntArg[i].vt = VT_R4;
252  vntArg[i].fltVal = (float) va_arg(list, double);
253  break;
254  case VT_BSTR:
255  vntArg[i].vt = VT_BSTR;
256  vntArg[i].bstrVal = va_arg(list, BSTR);
257  break;
258  case VT_VARIANT:
259  vntArg[i] = va_arg(list, VARIANT);
260  break;
261  default:
262  hr = E_INVALIDARG;
263  goto exit_proc;
264  }
265 
266  i++;
267  chArg += len;
268  }
269 
270  /* Sets send packet */
271  packet_send.id = id;
272  packet_send.argc = argc;
273  packet_send.args = vntArg;
274 
275  /* Sets receive packet */
276  packet_recv.argc = 1;
277  packet_recv.args = &vntRet;
278 
279  vt = 0;
280  pRet = NULL;
281  if (chRet != NULL) {
282  vt = atoi(chRet);
283  pRet = va_arg(list, void *);
284 
285  if ((pRet != NULL) && (vt == VT_VARIANT)) {
286  packet_recv.args = (VARIANT *) pRet;
287  }
288  }
289 
290  hr = send_receive(fd, &packet_send, &packet_recv);
291 
292  if (SUCCEEDED(hr)) {
293  if ((pRet == NULL) || (vt != vntRet.vt)) {
294  goto exit_proc;
295  }
296 
297  switch (vt) {
298  case VT_I4:
299  *(int32_t *) pRet = vntRet.lVal;
300  break;
301  case VT_BSTR:
302  *(BSTR *) pRet = SysAllocString(vntRet.bstrVal);
303  break;
304  default:
305  break;
306  }
307  }
308 
309 exit_proc:
310  va_end(list);
311 
312  if (vntArg != NULL) {
313  free(vntArg);
314  }
315 
316  VariantClear(&vntRet);
317 
318  return hr;
319 }
320 
321 HRESULT
322 bCap_Open_Client(const char* connect, uint32_t timeout, unsigned int retry,
323  int* pfd)
324 {
325  int index, *sock;
326  extern uint32_t tcp_conn_timeout;
327  HRESULT hr;
328  void *conn_param;
329  struct CONN_PARAM_ETH eth_param =
330  { inet_addr("127.0.0.1"), htons(5007), 0, 0 };
331  struct CONN_PARAM_COM com_param =
332  { 1, 38400, NOPARITY, 8, ONESTOPBIT, 0 };
333  struct CONN_BCAP_CLIENT *bcap_param;
334  struct CONN_PARAM_COMMON *device;
335  struct sockaddr_in *paddr;
336 
337  if (connect == NULL || pfd == NULL)
338  return E_INVALIDARG;
339 
340  index = find_open_address();
341  if (index == 0)
342  return E_MAX_OBJECT;
343 
344  bcap_param = &m_conn_param[index - 1];
345  device = &bcap_param->device;
346 
347  /* Initializes connection parameters */
348  device->type = parse_conn_type(connect);
349  switch (device->type) {
350  case CONN_TCP:
351  hr = parse_conn_param_ether(connect, &eth_param);
352  conn_param = &eth_param;
353  device->arg = NULL;
354  device->dn_open = &tcp_open_client;
355  device->dn_close = &tcp_close;
356  device->dn_send = &tcp_send;
357  device->dn_recv = &tcp_recv;
358  device->dn_set_timeout = &tcp_set_timeout;
359  tcp_conn_timeout = timeout;
360  break;
361  case CONN_UDP:
362  hr = parse_conn_param_ether(connect, &eth_param);
363  conn_param = &eth_param;
364  paddr = (struct sockaddr_in *) malloc(sizeof(struct sockaddr_in));
365  if (paddr == NULL) {
366  hr = E_OUTOFMEMORY;
367  break;
368  }
369  paddr->sin_addr.s_addr = eth_param.dst_addr;
370  paddr->sin_port = eth_param.dst_port;
371  paddr->sin_family = AF_INET;
372  device->arg = (void *) paddr;
373  device->dn_open = &udp_open;
374  device->dn_close = &udp_close;
375  device->dn_send = &udp_send;
376  device->dn_recv = &udp_recv;
377  device->dn_set_timeout = &udp_set_timeout;
378  break;
379  case CONN_COM:
380  hr = parse_conn_param_serial(connect, &com_param);
381  conn_param = &com_param;
382  device->arg = NULL;
383  device->dn_open = &com_open;
384  device->dn_close = &com_close;
385  device->dn_send = &com_send;
386  device->dn_recv = &com_recv;
387  device->dn_set_timeout = &com_set_timeout;
388  break;
389  default:
390  hr = E_INVALIDARG;
391  break;
392  }
393 
394  if (FAILED(hr)) {
395  if (device->arg != NULL) {
396  free(device->arg);
397  device->arg = NULL;
398  }
399  memset(bcap_param, 0, sizeof(struct CONN_BCAP_CLIENT));
400  return hr;
401  }
402 
403  /* Initializes mutex */
404  hr = initialize_mutex(&bcap_param->mutex);
405  if (FAILED(hr)) {
406  if (device->arg != NULL) {
407  free(device->arg);
408  device->arg = NULL;
409  }
410  return hr;
411  }
412 
413  /* Opens connection */
414  sock = &device->sock;
415  hr = device->dn_open(conn_param, sock);
416  if (FAILED(hr)) {
417  release_mutex(&bcap_param->mutex);
418  if (device->arg != NULL) {
419  free(device->arg);
420  device->arg = NULL;
421  }
422  memset(bcap_param, 0, sizeof(struct CONN_BCAP_CLIENT));
423  return hr;
424  }
425 
426  hr = bCap_SetTimeout(index, timeout);
427  if (FAILED(hr)) {
428  bCap_Close_Client(&index);
429  return hr;
430  }
431 
432  hr = bCap_SetRetry(index, retry);
433  if (FAILED(hr)) {
434  bCap_Close_Client(&index);
435  return hr;
436  }
437 
438  /* Sets parameters */
439  bcap_param->serial = 1;
440 
441  *pfd = index;
442 
443  return S_OK;
444 }
445 
446 HRESULT
448 {
449  int index, *sock;
450  struct CONN_BCAP_CLIENT *bcap_param;
451  struct CONN_PARAM_COMMON *device;
452 
453  if (pfd == NULL)
454  return E_HANDLE;
455 
456  index = *pfd;
457 
458  bcap_param = check_address(index);
459  if (bcap_param == NULL)
460  return E_HANDLE;
461 
462  device = &bcap_param->device;
463  sock = &device->sock;
464 
465  /* Releases mutex */
466  release_mutex(&bcap_param->mutex);
467 
468  /* Closes connection */
469  device->dn_close(sock);
470 
471  /* Releases argument */
472  if (device->arg != NULL) {
473  free(device->arg);
474  device->arg = NULL;
475  }
476 
477  /* Resets connection parameters */
478  memset(bcap_param, 0, sizeof(struct CONN_BCAP_CLIENT));
479 
480  *pfd = 0;
481 
482  return S_OK;
483 }
484 
485 HRESULT
487 {
488  int *sock;
489  HRESULT hr;
490  struct CONN_BCAP_CLIENT *bcap_param;
491  struct CONN_PARAM_COMMON *device;
492 
493  bcap_param = check_address(fd);
494  if (bcap_param == NULL)
495  return E_HANDLE;
496 
497  device = &bcap_param->device;
498  sock = &device->sock;
499 
500  /* Locks mutex and must not returns this function without end of one. */
501  hr = lock_mutex(&bcap_param->mutex, INFINITE);
502  if (FAILED(hr))
503  return hr;
504 
505  hr = device->dn_set_timeout(*sock, timeout);
506  if (SUCCEEDED(hr)) {
507  device->timeout = timeout;
508  }
509 
510  /* Unlocks mutex */
511  unlock_mutex(&bcap_param->mutex);
512 
513  return hr;
514 }
515 
516 HRESULT
518 {
519  struct CONN_BCAP_CLIENT *bcap_param;
520  struct CONN_PARAM_COMMON *device;
521 
522  bcap_param = check_address(fd);
523  if (bcap_param == NULL)
524  return E_HANDLE;
525 
526  if (timeout == NULL)
527  return E_INVALIDARG;
528 
529  device = &bcap_param->device;
530  *timeout = device->timeout;
531 
532  return S_OK;
533 }
534 
535 HRESULT
536 bCap_SetRetry(int fd, unsigned int retry)
537 {
538  HRESULT hr;
539  struct CONN_BCAP_CLIENT *bcap_param;
540  struct CONN_PARAM_COMMON *device;
541 
542  bcap_param = check_address(fd);
543  if (bcap_param == NULL)
544  return E_HANDLE;
545 
546  device = &bcap_param->device;
547 
548  /* Locks mutex and must not returns this function without end of one. */
549  hr = lock_mutex(&bcap_param->mutex, INFINITE);
550  if (FAILED(hr))
551  return hr;
552 
553  switch (device->type) {
554  case CONN_TCP:
555  bcap_param->retry = 1;
556  break;
557  case CONN_UDP:
558  case CONN_COM:
559  if (retry < _RETRY_MIN) {
560  bcap_param->retry = _RETRY_MIN;
561  }
562  else if (_RETRY_MAX < retry) {
563  bcap_param->retry = _RETRY_MAX;
564  }
565  else {
566  bcap_param->retry = retry;
567  }
568  break;
569  default:
570  hr = E_HANDLE;
571  break;
572  }
573 
574  /* Unlocks mutex */
575  unlock_mutex(&bcap_param->mutex);
576 
577  return hr;
578 }
579 
580 HRESULT
581 bCap_GetRetry(int fd, unsigned int *retry)
582 {
583  struct CONN_BCAP_CLIENT *bcap_param;
584 
585  bcap_param = check_address(fd);
586  if (bcap_param == NULL)
587  return E_HANDLE;
588 
589  if (retry == NULL)
590  return E_INVALIDARG;
591 
592  *retry = bcap_param->retry;
593 
594  return S_OK;
595 }
596 
597 HRESULT
598 bCap_ServiceStart(int fd, BSTR bstrOption)
599 {
600  char format[] = "8";
601  return invoke_function(fd, ID_SERVICE_START, 1, format, bstrOption);
602 }
603 
604 HRESULT
606 {
607  char format[] = "";
608  return invoke_function(fd, ID_SERVICE_STOP, 0, format);
609 }
610 
611 HRESULT
612 bCap_ControllerConnect(int fd, BSTR bstrName, BSTR bstrProvider,
613  BSTR bstrMachine, BSTR bstrOption, uint32_t *hController)
614 {
615  char format[] = "8,8,8,8:3";
616  if (hController == NULL)
617  return E_INVALIDARG;
618  return invoke_function(fd, ID_CONTROLLER_CONNECT, 4, format, bstrName,
619  bstrProvider, bstrMachine, bstrOption, hController);
620 }
621 
622 HRESULT
623 bCap_ControllerDisconnect(int fd, uint32_t *hController)
624 {
625  char format[] = "3";
626  HRESULT hr;
627 
628  if (hController == NULL)
629  return E_INVALIDARG;
630 
631  hr = invoke_function(fd, ID_CONTROLLER_DISCONNECT, 1, format, *hController);
632  if (SUCCEEDED(hr)) {
633  *hController = 0;
634  }
635 
636  return hr;
637 }
638 
639 HRESULT
640 bCap_ControllerGetExtension(int fd, uint32_t hController, BSTR bstrName,
641  BSTR bstrOption, uint32_t *hExtension)
642 {
643  char format[] = "3,8,8:3";
644  if (hExtension == NULL)
645  return E_INVALIDARG;
646  return invoke_function(fd, ID_CONTROLLER_GETEXTENSION, 3, format, hController,
647  bstrName, bstrOption, hExtension);
648 }
649 
650 HRESULT
651 bCap_ControllerGetFile(int fd, uint32_t hController, BSTR bstrName,
652  BSTR bstrOption, uint32_t *hFile)
653 {
654  char format[] = "3,8,8:3";
655  if (hFile == NULL)
656  return E_INVALIDARG;
657  return invoke_function(fd, ID_CONTROLLER_GETFILE, 3, format, hController,
658  bstrName, bstrOption, hFile);
659 }
660 
661 HRESULT
662 bCap_ControllerGetRobot(int fd, uint32_t hController, BSTR bstrName,
663  BSTR bstrOption, uint32_t *hRobot)
664 {
665  char format[] = "3,8,8:3";
666  if (hRobot == NULL)
667  return E_INVALIDARG;
668  return invoke_function(fd, ID_CONTROLLER_GETROBOT, 3, format, hController,
669  bstrName, bstrOption, hRobot);
670 }
671 
672 HRESULT
673 bCap_ControllerGetTask(int fd, uint32_t hController, BSTR bstrName,
674  BSTR bstrOption, uint32_t *hTask)
675 {
676  char format[] = "3,8,8:3";
677  if (hTask == NULL)
678  return E_INVALIDARG;
679  return invoke_function(fd, ID_CONTROLLER_GETTASK, 3, format, hController,
680  bstrName, bstrOption, hTask);
681 }
682 
683 HRESULT
684 bCap_ControllerGetVariable(int fd, uint32_t hController, BSTR bstrName,
685  BSTR bstrOption, uint32_t *hVariable)
686 {
687  char format[] = "3,8,8:3";
688  if (hVariable == NULL)
689  return E_INVALIDARG;
690  return invoke_function(fd, ID_CONTROLLER_GETVARIABLE, 3, format, hController,
691  bstrName, bstrOption, hVariable);
692 }
693 
694 HRESULT
695 bCap_ControllerGetCommand(int fd, uint32_t hController, BSTR bstrName,
696  BSTR bstrOption, uint32_t *hCommand)
697 {
698  char format[] = "3,8,8:3";
699  if (hCommand == NULL)
700  return E_INVALIDARG;
701  return invoke_function(fd, ID_CONTROLLER_GETCOMMAND, 3, format, hController,
702  bstrName, bstrOption, hCommand);
703 }
704 
705 HRESULT
706 bCap_ControllerGetExtensionNames(int fd, uint32_t hController, BSTR bstrOption,
707  VARIANT *pVal)
708 {
709  char format[] = "3,8:12";
710  return invoke_function(fd, ID_CONTROLLER_GETEXTENSIONNAMES, 2, format,
711  hController, bstrOption, pVal);
712 }
713 
714 HRESULT
715 bCap_ControllerGetFileNames(int fd, uint32_t hController, BSTR bstrOption,
716  VARIANT *pVal)
717 {
718  char format[] = "3,8:12";
719  return invoke_function(fd, ID_CONTROLLER_GETFILENAMES, 2, format, hController,
720  bstrOption, pVal);
721 }
722 
723 HRESULT
724 bCap_ControllerGetRobotNames(int fd, uint32_t hController, BSTR bstrOption,
725  VARIANT *pVal)
726 {
727  char format[] = "3,8:12";
728  return invoke_function(fd, ID_CONTROLLER_GETROBOTNAMES, 2, format,
729  hController, bstrOption, pVal);
730 }
731 
732 HRESULT
733 bCap_ControllerGetTaskNames(int fd, uint32_t hController, BSTR bstrOption,
734  VARIANT *pVal)
735 {
736  char format[] = "3,8:12";
737  return invoke_function(fd, ID_CONTROLLER_GETTASKNAMES, 2, format, hController,
738  bstrOption, pVal);
739 }
740 
741 HRESULT
742 bCap_ControllerGetVariableNames(int fd, uint32_t hController, BSTR bstrOption,
743  VARIANT *pVal)
744 {
745  char format[] = "3,8:12";
746  return invoke_function(fd, ID_CONTROLLER_GETVARIABLENAMES, 2, format,
747  hController, bstrOption, pVal);
748 }
749 
750 HRESULT
751 bCap_ControllerGetCommandNames(int fd, uint32_t hController, BSTR bstrOption,
752  VARIANT *pVal)
753 {
754  char format[] = "3,8:12";
755  return invoke_function(fd, ID_CONTROLLER_GETCOMMANDNAMES, 2, format,
756  hController, bstrOption, pVal);
757 }
758 
759 HRESULT
760 bCap_ControllerExecute(int fd, uint32_t hController, BSTR bstrCommand,
761  VARIANT vntParam, VARIANT *pVal)
762 {
763  char format[] = "3,8,12:12";
764  return invoke_function(fd, ID_CONTROLLER_EXECUTE, 3, format, hController,
765  bstrCommand, vntParam, pVal);
766 }
767 
768 HRESULT
769 bCap_ControllerGetMessage(int fd, uint32_t hController, uint32_t *hMessage)
770 {
771  char format[] = "3:3";
772  if (hMessage == NULL)
773  return E_INVALIDARG;
774  return invoke_function(fd, ID_CONTROLLER_GETMESSAGE, 1, format, hController,
775  hMessage);
776 }
777 
778 HRESULT
779 bCap_ControllerGetAttribute(int fd, uint32_t hController, int32_t *pVal)
780 {
781  char format[] = "3:3";
782  return invoke_function(fd, ID_CONTROLLER_GETATTRIBUTE, 1, format, hController,
783  pVal);
784 }
785 
786 HRESULT
787 bCap_ControllerGetHelp(int fd, uint32_t hController, BSTR *pVal)
788 {
789  char format[] = "3:8";
790  return invoke_function(fd, ID_CONTROLLER_GETHELP, 1, format, hController,
791  pVal);
792 }
793 
794 HRESULT
795 bCap_ControllerGetName(int fd, uint32_t hController, BSTR *pVal)
796 {
797  char format[] = "3:8";
798  return invoke_function(fd, ID_CONTROLLER_GETNAME, 1, format, hController,
799  pVal);
800 }
801 
802 HRESULT
803 bCap_ControllerGetTag(int fd, uint32_t hController, VARIANT *pVal)
804 {
805  char format[] = "3:12";
806  return invoke_function(fd, ID_CONTROLLER_GETTAG, 1, format, hController, pVal);
807 }
808 
809 HRESULT
810 bCap_ControllerPutTag(int fd, uint32_t hController, VARIANT newVal)
811 {
812  char format[] = "3,12";
813  return invoke_function(fd, ID_CONTROLLER_PUTTAG, 2, format, hController,
814  newVal);
815 }
816 
817 HRESULT
818 bCap_ControllerGetID(int fd, uint32_t hController, VARIANT *pVal)
819 {
820  char format[] = "3:12";
821  return invoke_function(fd, ID_CONTROLLER_GETID, 1, format, hController, pVal);
822 }
823 
824 HRESULT
825 bCap_ControllerPutID(int fd, uint32_t hController, VARIANT newVal)
826 {
827  char format[] = "3,12";
828  return invoke_function(fd, ID_CONTROLLER_PUTID, 2, format, hController,
829  newVal);
830 }
831 
832 HRESULT
833 bCap_ExtensionGetVariable(int fd, uint32_t hExtension, BSTR bstrName,
834  BSTR bstrOption, uint32_t *hVariable)
835 {
836  char format[] = "3,8,8:3";
837  if (hVariable == NULL)
838  return E_INVALIDARG;
839  return invoke_function(fd, ID_EXTENSION_GETVARIABLE, 3, format, hExtension,
840  bstrName, bstrOption, hVariable);
841 }
842 
843 HRESULT
844 bCap_ExtensionGetVariableNames(int fd, uint32_t hExtension, BSTR bstrOption,
845  VARIANT *pVal)
846 {
847  char format[] = "3,8:12";
848  return invoke_function(fd, ID_EXTENSION_GETVARIABLENAMES, 2, format,
849  hExtension, bstrOption, pVal);
850 }
851 
852 HRESULT
853 bCap_ExtensionExecute(int fd, uint32_t hExtension, BSTR bstrCommand,
854  VARIANT vntParam, VARIANT *pVal)
855 {
856  char format[] = "3,8,12:12";
857  return invoke_function(fd, ID_EXTENSION_EXECUTE, 3, format, hExtension,
858  bstrCommand, vntParam, pVal);
859 }
860 
861 HRESULT
862 bCap_ExtensionGetAttribute(int fd, uint32_t hExtension, int32_t *pVal)
863 {
864  char format[] = "3:3";
865  return invoke_function(fd, ID_EXTENSION_GETATTRIBUTE, 1, format, hExtension,
866  pVal);
867 }
868 
869 HRESULT
870 bCap_ExtensionGetHelp(int fd, uint32_t hExtension, BSTR *pVal)
871 {
872  char format[] = "3:8";
873  return invoke_function(fd, ID_EXTENSION_GETHELP, 1, format, hExtension, pVal);
874 }
875 
876 HRESULT
877 bCap_ExtensionGetName(int fd, uint32_t hExtension, BSTR *pVal)
878 {
879  char format[] = "3:8";
880  return invoke_function(fd, ID_EXTENSION_GETNAME, 1, format, hExtension, pVal);
881 }
882 
883 HRESULT
884 bCap_ExtensionGetTag(int fd, uint32_t hExtension, VARIANT *pVal)
885 {
886  char format[] = "3:12";
887  return invoke_function(fd, ID_EXTENSION_GETTAG, 1, format, hExtension, pVal);
888 }
889 
890 HRESULT
891 bCap_ExtensionPutTag(int fd, uint32_t hExtension, VARIANT newVal)
892 {
893  char format[] = "3,12";
894  return invoke_function(fd, ID_EXTENSION_PUTTAG, 2, format, hExtension, newVal);
895 }
896 
897 HRESULT
898 bCap_ExtensionGetID(int fd, uint32_t hExtension, VARIANT *pVal)
899 {
900  char format[] = "3:12";
901  return invoke_function(fd, ID_EXTENSION_GETID, 1, format, hExtension, pVal);
902 }
903 
904 HRESULT
905 bCap_ExtensionPutID(int fd, uint32_t hExtension, VARIANT newVal)
906 {
907  char format[] = "3,12";
908  return invoke_function(fd, ID_EXTENSION_PUTID, 2, format, hExtension, newVal);
909 }
910 
911 HRESULT
912 bCap_ExtensionRelease(int fd, uint32_t *hExtension)
913 {
914  char format[] = "3";
915  HRESULT hr;
916 
917  if (hExtension == NULL)
918  return E_INVALIDARG;
919 
920  hr = invoke_function(fd, ID_EXTENSION_RELEASE, 1, format, *hExtension);
921  if (SUCCEEDED(hr)) {
922  *hExtension = 0;
923  }
924 
925  return hr;
926 }
927 
928 HRESULT
929 bCap_FileGetFile(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption,
930  uint32_t *hFile2)
931 {
932  char format[] = "3,8,8:3";
933  if (hFile2 == NULL)
934  return E_INVALIDARG;
935  return invoke_function(fd, ID_FILE_GETFILE, 3, format, hFile, bstrName,
936  bstrOption, hFile2);
937 }
938 
939 HRESULT
940 bCap_FileGetVariable(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption,
941  uint32_t *hVariable)
942 {
943  char format[] = "3,8,8:3";
944  if (hVariable == NULL)
945  return E_INVALIDARG;
946  return invoke_function(fd, ID_FILE_GETVARIABLE, 3, format, hFile, bstrName,
947  bstrOption, hVariable);
948 }
949 
950 HRESULT
951 bCap_FileGetFileNames(int fd, uint32_t hFile, BSTR bstrOption, VARIANT *pVal)
952 {
953  char format[] = "3,8:12";
954  return invoke_function(fd, ID_FILE_GETFILENAMES, 2, format, hFile, bstrOption,
955  pVal);
956 }
957 
958 HRESULT
959 bCap_FileGetVariableNames(int fd, uint32_t hFile, BSTR bstrOption,
960  VARIANT *pVal)
961 {
962  char format[] = "3,8:12";
963  return invoke_function(fd, ID_FILE_GETVARIABLENAMES, 2, format, hFile,
964  bstrOption, pVal);
965 }
966 
967 HRESULT
968 bCap_FileExecute(int fd, uint32_t hFile, BSTR bstrCommand, VARIANT vntParam,
969  VARIANT *pVal)
970 {
971  char format[] = "3,8,12:12";
972  return invoke_function(fd, ID_FILE_EXECUTE, 3, format, hFile, bstrCommand,
973  vntParam, pVal);
974 }
975 
976 HRESULT
977 bCap_FileCopy(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption)
978 {
979  char format[] = "3,8,8";
980  return invoke_function(fd, ID_FILE_COPY, 3, format, hFile, bstrName,
981  bstrOption);
982 }
983 
984 HRESULT
985 bCap_FileDelete(int fd, uint32_t hFile, BSTR bstrOption)
986 {
987  char format[] = "3,8";
988  return invoke_function(fd, ID_FILE_DELETE, 2, format, hFile, bstrOption);
989 }
990 
991 HRESULT
992 bCap_FileMove(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption)
993 {
994  char format[] = "3,8,8";
995  return invoke_function(fd, ID_FILE_MOVE, 3, format, hFile, bstrName,
996  bstrOption);
997 }
998 
999 HRESULT
1000 bCap_FileRun(int fd, uint32_t hFile, BSTR bstrOption, BSTR *pVal)
1001 {
1002  char format[] = "3,8:8";
1003  return invoke_function(fd, ID_FILE_RUN, 2, format, hFile, bstrOption, pVal);
1004 }
1005 
1006 HRESULT
1008 {
1009  char format[] = "3:12";
1010  return invoke_function(fd, ID_FILE_GETDATECREATED, 1, format, hFile, pVal);
1011 }
1012 
1013 HRESULT
1015 {
1016  char format[] = "3:12";
1017  return invoke_function(fd, ID_FILE_GETDATELASTACCESSED, 1, format, hFile,
1018  pVal);
1019 }
1020 
1021 HRESULT
1023 {
1024  char format[] = "3:12";
1025  return invoke_function(fd, ID_FILE_GETDATELASTMODIFIED, 1, format, hFile,
1026  pVal);
1027 }
1028 
1029 HRESULT
1030 bCap_FileGetPath(int fd, uint32_t hFile, BSTR *pVal)
1031 {
1032  char format[] = "3:8";
1033  return invoke_function(fd, ID_FILE_GETPATH, 1, format, hFile, pVal);
1034 }
1035 
1036 HRESULT
1037 bCap_FileGetSize(int fd, uint32_t hFile, int32_t *pVal)
1038 {
1039  char format[] = "3:3";
1040  return invoke_function(fd, ID_FILE_GETSIZE, 1, format, hFile, pVal);
1041 }
1042 
1043 HRESULT
1044 bCap_FileGetType(int fd, uint32_t hFile, BSTR *pVal)
1045 {
1046  char format[] = "3:8";
1047  return invoke_function(fd, ID_FILE_GETTYPE, 1, format, hFile, pVal);
1048 }
1049 
1050 HRESULT
1051 bCap_FileGetValue(int fd, uint32_t hFile, VARIANT *pVal)
1052 {
1053  char format[] = "3:12";
1054  return invoke_function(fd, ID_FILE_GETVALUE, 1, format, hFile, pVal);
1055 }
1056 
1057 HRESULT
1058 bCap_FilePutValue(int fd, uint32_t hFile, VARIANT newVal)
1059 {
1060  char format[] = "3,12";
1061  return invoke_function(fd, ID_FILE_PUTVALUE, 2, format, hFile, newVal);
1062 }
1063 
1064 HRESULT
1066 {
1067  char format[] = "3:3";
1068  return invoke_function(fd, ID_FILE_GETATTRIBUTE, 1, format, hFile, pVal);
1069 }
1070 
1071 HRESULT
1072 bCap_FileGetHelp(int fd, uint32_t hFile, BSTR *pVal)
1073 {
1074  char format[] = "3:8";
1075  return invoke_function(fd, ID_FILE_GETHELP, 1, format, hFile, pVal);
1076 }
1077 
1078 HRESULT
1079 bCap_FileGetName(int fd, uint32_t hFile, BSTR *pVal)
1080 {
1081  char format[] = "3:8";
1082  return invoke_function(fd, ID_FILE_GETNAME, 1, format, hFile, pVal);
1083 }
1084 
1085 HRESULT
1086 bCap_FileGetTag(int fd, uint32_t hFile, VARIANT *pVal)
1087 {
1088  char format[] = "3:12";
1089  return invoke_function(fd, ID_FILE_GETTAG, 1, format, hFile, pVal);
1090 }
1091 
1092 HRESULT
1093 bCap_FilePutTag(int fd, uint32_t hFile, VARIANT newVal)
1094 {
1095  char format[] = "3,12";
1096  return invoke_function(fd, ID_FILE_PUTTAG, 2, format, hFile, newVal);
1097 }
1098 
1099 HRESULT
1100 bCap_FileGetID(int fd, uint32_t hFile, VARIANT *pVal)
1101 {
1102  char format[] = "3:12";
1103  return invoke_function(fd, ID_FILE_GETID, 1, format, hFile, pVal);
1104 }
1105 
1106 HRESULT
1107 bCap_FilePutID(int fd, uint32_t hFile, VARIANT newVal)
1108 {
1109  char format[] = "3,12";
1110  return invoke_function(fd, ID_FILE_PUTID, 2, format, hFile, newVal);
1111 }
1112 
1113 HRESULT
1115 {
1116  char format[] = "3";
1117  HRESULT hr;
1118 
1119  if (hFile == NULL)
1120  return E_INVALIDARG;
1121 
1122  hr = invoke_function(fd, ID_FILE_RELEASE, 1, format, *hFile);
1123  if (SUCCEEDED(hr)) {
1124  *hFile = 0;
1125  }
1126 
1127  return hr;
1128 }
1129 
1130 HRESULT
1131 bCap_RobotGetVariable(int fd, uint32_t hRobot, BSTR bstrName, BSTR bstrOption,
1132  uint32_t *hVariable)
1133 {
1134  char format[] = "3,8,8:3";
1135  if (hVariable == NULL)
1136  return E_INVALIDARG;
1137  return invoke_function(fd, ID_ROBOT_GETVARIABLE, 3, format, hRobot, bstrName,
1138  bstrOption, hVariable);
1139 }
1140 
1141 HRESULT
1142 bCap_RobotGetVariableNames(int fd, uint32_t hRobot, BSTR bstrOption,
1143  VARIANT *pVal)
1144 {
1145  char format[] = "3,8:12";
1146  return invoke_function(fd, ID_ROBOT_GETVARIABLENAMES, 2, format, hRobot,
1147  bstrOption, pVal);
1148 }
1149 
1150 HRESULT
1151 bCap_RobotExecute(int fd, uint32_t hRobot, BSTR bstrCommand, VARIANT vntParam,
1152  VARIANT *pVal)
1153 {
1154  char format[] = "3,8,12:12";
1155  return invoke_function(fd, ID_ROBOT_EXECUTE, 3, format, hRobot, bstrCommand,
1156  vntParam, pVal);
1157 }
1158 
1159 HRESULT
1160 bCap_RobotAccelerate(int fd, uint32_t hRobot, int32_t lAxis, float fAccel,
1161  float fDecel)
1162 {
1163  char format[] = "3,3,4,4";
1164  return invoke_function(fd, ID_ROBOT_ACCELERATE, 4, format, hRobot, lAxis,
1165  fAccel, fDecel);
1166 }
1167 
1168 HRESULT
1169 bCap_RobotChange(int fd, uint32_t hRobot, BSTR bstrName)
1170 {
1171  char format[] = "3,8";
1172  return invoke_function(fd, ID_ROBOT_CHANGE, 2, format, hRobot, bstrName);
1173 }
1174 
1175 HRESULT
1176 bCap_RobotChuck(int fd, uint32_t hRobot, BSTR bstrOption)
1177 {
1178  char format[] = "3,8";
1179  return invoke_function(fd, ID_ROBOT_CHUCK, 2, format, hRobot, bstrOption);
1180 }
1181 
1182 HRESULT
1183 bCap_RobotDrive(int fd, uint32_t hRobot, int32_t lNo, float fMov,
1184  BSTR bstrOption)
1185 {
1186  char format[] = "3,3,4,8";
1187  return invoke_function(fd, ID_ROBOT_DRIVE, 4, format, hRobot, lNo, fMov,
1188  bstrOption);
1189 }
1190 
1191 HRESULT
1193 {
1194  char format[] = "3";
1195  return invoke_function(fd, ID_ROBOT_GOHOME, 1, format, hRobot);
1196 }
1197 
1198 HRESULT
1199 bCap_RobotHalt(int fd, uint32_t hRobot, BSTR bstrOption)
1200 {
1201  char format[] = "3,8";
1202  return invoke_function(fd, ID_ROBOT_HALT, 2, format, hRobot, bstrOption);
1203 }
1204 
1205 HRESULT
1206 bCap_RobotHold(int fd, uint32_t hRobot, BSTR bstrOption)
1207 {
1208  char format[] = "3,8";
1209  return invoke_function(fd, ID_ROBOT_HOLD, 2, format, hRobot, bstrOption);
1210 }
1211 
1212 HRESULT
1213 bCap_RobotMove(int fd, uint32_t hRobot, int32_t lComp, VARIANT vntPose,
1214  BSTR bstrOption)
1215 {
1216  char format[] = "3,3,12,8";
1217  return invoke_function(fd, ID_ROBOT_MOVE, 4, format, hRobot, lComp, vntPose,
1218  bstrOption);
1219 }
1220 
1221 HRESULT
1222 bCap_RobotRotate(int fd, uint32_t hRobot, VARIANT vntRotSuf, float fDeg,
1223  VARIANT vntPivot, BSTR bstrOption)
1224 {
1225  char format[] = "3,12,4,12,8";
1226  return invoke_function(fd, ID_ROBOT_ROTATE, 5, format, hRobot, vntRotSuf,
1227  fDeg, vntPivot, bstrOption);
1228 }
1229 
1230 HRESULT
1231 bCap_RobotSpeed(int fd, uint32_t hRobot, int32_t lAxis, float fSpeed)
1232 {
1233  char format[] = "3,3,4";
1234  return invoke_function(fd, ID_ROBOT_SPEED, 3, format, hRobot, lAxis, fSpeed);
1235 }
1236 
1237 HRESULT
1238 bCap_RobotUnchuck(int fd, uint32_t hRobot, BSTR bstrOption)
1239 {
1240  char format[] = "3,8";
1241  return invoke_function(fd, ID_ROBOT_UNCHUCK, 2, format, hRobot, bstrOption);
1242 }
1243 
1244 HRESULT
1245 bCap_RobotUnhold(int fd, uint32_t hRobot, BSTR bstrOption)
1246 {
1247  char format[] = "3,8";
1248  return invoke_function(fd, ID_ROBOT_UNHOLD, 2, format, hRobot, bstrOption);
1249 }
1250 
1251 HRESULT
1253 {
1254  char format[] = "3:3";
1255  return invoke_function(fd, ID_ROBOT_GETATTRIBUTE, 1, format, hRobot, pVal);
1256 }
1257 
1258 HRESULT
1259 bCap_RobotGetHelp(int fd, uint32_t hRobot, BSTR *pVal)
1260 {
1261  char format[] = "3:8";
1262  return invoke_function(fd, ID_ROBOT_GETHELP, 1, format, hRobot, pVal);
1263 }
1264 
1265 HRESULT
1266 bCap_RobotGetName(int fd, uint32_t hRobot, BSTR *pVal)
1267 {
1268  char format[] = "3:8";
1269  return invoke_function(fd, ID_ROBOT_GETNAME, 1, format, hRobot, pVal);
1270 }
1271 
1272 HRESULT
1273 bCap_RobotGetTag(int fd, uint32_t hRobot, VARIANT *pVal)
1274 {
1275  char format[] = "3:12";
1276  return invoke_function(fd, ID_ROBOT_GETTAG, 1, format, hRobot, pVal);
1277 }
1278 
1279 HRESULT
1280 bCap_RobotPutTag(int fd, uint32_t hRobot, VARIANT newVal)
1281 {
1282  char format[] = "3,12";
1283  return invoke_function(fd, ID_ROBOT_PUTTAG, 2, format, hRobot, newVal);
1284 }
1285 
1286 HRESULT
1287 bCap_RobotGetID(int fd, uint32_t hRobot, VARIANT *pVal)
1288 {
1289  char format[] = "3:12";
1290  return invoke_function(fd, ID_ROBOT_GETID, 1, format, hRobot, pVal);
1291 }
1292 
1293 HRESULT
1294 bCap_RobotPutID(int fd, uint32_t hRobot, VARIANT newVal)
1295 {
1296  char format[] = "3,12";
1297  return invoke_function(fd, ID_ROBOT_PUTID, 2, format, hRobot, newVal);
1298 }
1299 
1300 HRESULT
1301 bCap_RobotRelease(int fd, uint32_t *hRobot)
1302 {
1303  char format[] = "3";
1304  HRESULT hr;
1305 
1306  if (hRobot == NULL)
1307  return E_INVALIDARG;
1308 
1309  hr = invoke_function(fd, ID_ROBOT_RELEASE, 1, format, *hRobot);
1310  if (SUCCEEDED(hr)) {
1311  *hRobot = 0;
1312  }
1313 
1314  return hr;
1315 }
1316 
1317 HRESULT
1318 bCap_TaskGetVariable(int fd, uint32_t hTask, BSTR bstrName, BSTR bstrOption,
1319  uint32_t *hVariable)
1320 {
1321  char format[] = "3,8,8:3";
1322  if (hVariable == NULL)
1323  return E_INVALIDARG;
1324  return invoke_function(fd, ID_TASK_GETVARIABLE, 3, format, hTask, bstrName,
1325  bstrOption, hVariable);
1326 }
1327 
1328 HRESULT
1329 bCap_TaskGetVariableNames(int fd, uint32_t hTask, BSTR bstrOption,
1330  VARIANT *pVal)
1331 {
1332  char format[] = "3,8:12";
1333  return invoke_function(fd, ID_TASK_GETVARIABLENAMES, 2, format, hTask,
1334  bstrOption, pVal);
1335 }
1336 
1337 HRESULT
1338 bCap_TaskExecute(int fd, uint32_t hTask, BSTR bstrCommand, VARIANT vntParam,
1339  VARIANT *pVal)
1340 {
1341  char format[] = "3,8,12:12";
1342  return invoke_function(fd, ID_TASK_EXECUTE, 3, format, hTask, bstrCommand,
1343  vntParam, pVal);
1344 }
1345 
1346 HRESULT
1347 bCap_TaskStart(int fd, uint32_t hTask, int32_t lMode, BSTR bstrOption)
1348 {
1349  char format[] = "3,3,8";
1350  return invoke_function(fd, ID_TASK_START, 3, format, hTask, lMode, bstrOption);
1351 }
1352 
1353 HRESULT
1354 bCap_TaskStop(int fd, uint32_t hTask, int32_t lMode, BSTR bstrOption)
1355 {
1356  char format[] = "3,3,8";
1357  return invoke_function(fd, ID_TASK_STOP, 3, format, hTask, lMode, bstrOption);
1358 }
1359 
1360 HRESULT
1361 bCap_TaskDelete(int fd, uint32_t hTask, BSTR bstrOption)
1362 {
1363  char format[] = "3,8";
1364  return invoke_function(fd, ID_TASK_DELETE, 2, format, hTask, bstrOption);
1365 }
1366 
1367 HRESULT
1368 bCap_TaskGetFileName(int fd, uint32_t hTask, BSTR *pVal)
1369 {
1370  char format[] = "3:8";
1371  return invoke_function(fd, ID_TASK_GETFILENAME, 1, format, hTask, pVal);
1372 }
1373 
1374 HRESULT
1376 {
1377  char format[] = "3:3";
1378  return invoke_function(fd, ID_TASK_GETATTRIBUTE, 1, format, hTask, pVal);
1379 }
1380 
1381 HRESULT
1382 bCap_TaskGetHelp(int fd, uint32_t hTask, BSTR *pVal)
1383 {
1384  char format[] = "3:8";
1385  return invoke_function(fd, ID_TASK_GETHELP, 1, format, hTask, pVal);
1386 }
1387 
1388 HRESULT
1389 bCap_TaskGetName(int fd, uint32_t hTask, BSTR *pVal)
1390 {
1391  char format[] = "3:8";
1392  return invoke_function(fd, ID_TASK_GETNAME, 1, format, hTask, pVal);
1393 }
1394 
1395 HRESULT
1396 bCap_TaskGetTag(int fd, uint32_t hTask, VARIANT *pVal)
1397 {
1398  char format[] = "3:12";
1399  return invoke_function(fd, ID_TASK_GETTAG, 1, format, hTask, pVal);
1400 }
1401 
1402 HRESULT
1403 bCap_TaskPutTag(int fd, uint32_t hTask, VARIANT newVal)
1404 {
1405  char format[] = "3,12";
1406  return invoke_function(fd, ID_TASK_PUTTAG, 2, format, hTask, newVal);
1407 }
1408 
1409 HRESULT
1410 bCap_TaskGetID(int fd, uint32_t hTask, VARIANT *pVal)
1411 {
1412  char format[] = "3:12";
1413  return invoke_function(fd, ID_TASK_GETID, 1, format, hTask, pVal);
1414 }
1415 
1416 HRESULT
1417 bCap_TaskPutID(int fd, uint32_t hTask, VARIANT newVal)
1418 {
1419  char format[] = "3,12";
1420  return invoke_function(fd, ID_TASK_PUTID, 2, format, hTask, newVal);
1421 }
1422 
1423 HRESULT
1425 {
1426  char format[] = "3";
1427  HRESULT hr;
1428 
1429  if (hTask == NULL)
1430  return E_INVALIDARG;
1431 
1432  hr = invoke_function(fd, ID_TASK_RELEASE, 1, format, *hTask);
1433  if (SUCCEEDED(hr)) {
1434  *hTask = 0;
1435  }
1436 
1437  return hr;
1438 }
1439 
1440 HRESULT
1441 bCap_VariableGetDateTime(int fd, uint32_t hVariable, VARIANT *pVal)
1442 {
1443  char format[] = "3:12";
1444  return invoke_function(fd, ID_VARIABLE_GETDATETIME, 1, format, hVariable,
1445  pVal);
1446 }
1447 
1448 HRESULT
1449 bCap_VariableGetValue(int fd, uint32_t hVariable, VARIANT *pVal)
1450 {
1451  char format[] = "3:12";
1452  return invoke_function(fd, ID_VARIABLE_GETVALUE, 1, format, hVariable, pVal);
1453 }
1454 
1455 HRESULT
1456 bCap_VariablePutValue(int fd, uint32_t hVariable, VARIANT newVal)
1457 {
1458  char format[] = "3,12";
1459  return invoke_function(fd, ID_VARIABLE_PUTVALUE, 2, format, hVariable, newVal);
1460 }
1461 
1462 HRESULT
1463 bCap_VariableGetAttribute(int fd, uint32_t hVariable, int32_t *pVal)
1464 {
1465  char format[] = "3:3";
1466  return invoke_function(fd, ID_VARIABLE_GETATTRIBUTE, 1, format, hVariable,
1467  pVal);
1468 }
1469 
1470 HRESULT
1471 bCap_VariableGetHelp(int fd, uint32_t hVariable, BSTR *pVal)
1472 {
1473  char format[] = "3:8";
1474  return invoke_function(fd, ID_VARIABLE_GETHELP, 1, format, hVariable, pVal);
1475 }
1476 
1477 HRESULT
1478 bCap_VariableGetName(int fd, uint32_t hVariable, BSTR *pVal)
1479 {
1480  char format[] = "3:8";
1481  return invoke_function(fd, ID_VARIABLE_GETNAME, 1, format, hVariable, pVal);
1482 }
1483 
1484 HRESULT
1485 bCap_VariableGetTag(int fd, uint32_t hVariable, VARIANT *pVal)
1486 {
1487  char format[] = "3:12";
1488  return invoke_function(fd, ID_VARIABLE_GETTAG, 1, format, hVariable, pVal);
1489 }
1490 
1491 HRESULT
1492 bCap_VariablePutTag(int fd, uint32_t hVariable, VARIANT newVal)
1493 {
1494  char format[] = "3,12";
1495  return invoke_function(fd, ID_VARIABLE_PUTTAG, 2, format, hVariable, newVal);
1496 }
1497 
1498 HRESULT
1499 bCap_VariableGetID(int fd, uint32_t hVariable, VARIANT *pVal)
1500 {
1501  char format[] = "3:12";
1502  return invoke_function(fd, ID_VARIABLE_GETID, 1, format, hVariable, pVal);
1503 }
1504 
1505 HRESULT
1506 bCap_VariablePutID(int fd, uint32_t hVariable, VARIANT newVal)
1507 {
1508  char format[] = "3,12";
1509  return invoke_function(fd, ID_VARIABLE_PUTID, 2, format, hVariable, newVal);
1510 }
1511 
1512 HRESULT
1514 {
1515  char format[] = "3:3";
1516  return invoke_function(fd, ID_VARIABLE_GETMICROSECOND, 1, format, hVariable,
1517  pVal);
1518 }
1519 
1520 HRESULT
1521 bCap_VariableRelease(int fd, uint32_t *hVariable)
1522 {
1523  char format[] = "3";
1524  HRESULT hr;
1525 
1526  if (hVariable == NULL)
1527  return E_INVALIDARG;
1528 
1529  hr = invoke_function(fd, ID_VARIABLE_RELEASE, 1, format, *hVariable);
1530  if (SUCCEEDED(hr)) {
1531  *hVariable = 0;
1532  }
1533 
1534  return hr;
1535 }
1536 
1537 HRESULT
1538 bCap_CommandExecute(int fd, uint32_t hCommand, int32_t lMode, VARIANT *pVal)
1539 {
1540  char format[] = "3,3:12";
1541  return invoke_function(fd, ID_COMMAND_EXECUTE, 2, format, hCommand, lMode,
1542  pVal);
1543 }
1544 
1545 HRESULT
1546 bCap_CommandCancel(int fd, uint32_t hCommand)
1547 {
1548  char format[] = "3";
1549  return invoke_function(fd, ID_COMMAND_CANCEL, 1, format, hCommand);
1550 }
1551 
1552 HRESULT
1553 bCap_CommandGetTimeout(int fd, uint32_t hCommand, int32_t *pVal)
1554 {
1555  char format[] = "3:3";
1556  return invoke_function(fd, ID_COMMAND_GETTIMEOUT, 1, format, hCommand, pVal);
1557 }
1558 
1559 HRESULT
1560 bCap_CommandPutTimeout(int fd, uint32_t hCommand, int32_t newVal)
1561 {
1562  char format[] = "3,3";
1563  return invoke_function(fd, ID_COMMAND_PUTTIMEOUT, 2, format, hCommand, newVal);
1564 }
1565 
1566 HRESULT
1567 bCap_CommandGetState(int fd, uint32_t hCommand, int32_t *pVal)
1568 {
1569  char format[] = "3:3";
1570  return invoke_function(fd, ID_COMMAND_GETSTATE, 1, format, hCommand, pVal);
1571 }
1572 
1573 HRESULT
1575 {
1576  char format[] = "3:12";
1577  return invoke_function(fd, ID_COMMAND_GETPARAMETERS, 1, format, hCommand,
1578  pVal);
1579 }
1580 
1581 HRESULT
1582 bCap_CommandPutParameters(int fd, uint32_t hCommand, VARIANT newVal)
1583 {
1584  char format[] = "3,12";
1585  return invoke_function(fd, ID_COMMAND_PUTPARAMETERS, 2, format, hCommand,
1586  newVal);
1587 }
1588 
1589 HRESULT
1590 bCap_CommandGetResult(int fd, uint32_t hCommand, VARIANT *pVal)
1591 {
1592  char format[] = "3:12";
1593  return invoke_function(fd, ID_COMMAND_GETRESULT, 1, format, hCommand, pVal);
1594 }
1595 
1596 HRESULT
1598 {
1599  char format[] = "3:3";
1600  return invoke_function(fd, ID_COMMAND_GETATTRIBUTE, 1, format, hCommand, pVal);
1601 }
1602 
1603 HRESULT
1604 bCap_CommandGetHelp(int fd, uint32_t hCommand, BSTR *pVal)
1605 {
1606  char format[] = "3:8";
1607  return invoke_function(fd, ID_COMMAND_GETHELP, 1, format, hCommand, pVal);
1608 }
1609 
1610 HRESULT
1611 bCap_CommandGetName(int fd, uint32_t hCommand, BSTR *pVal)
1612 {
1613  char format[] = "3:8";
1614  return invoke_function(fd, ID_COMMAND_GETNAME, 1, format, hCommand, pVal);
1615 }
1616 
1617 HRESULT
1618 bCap_CommandGetTag(int fd, uint32_t hCommand, VARIANT *pVal)
1619 {
1620  char format[] = "3:12";
1621  return invoke_function(fd, ID_COMMAND_GETTAG, 1, format, hCommand, pVal);
1622 }
1623 
1624 HRESULT
1625 bCap_CommandPutTag(int fd, uint32_t hCommand, VARIANT newVal)
1626 {
1627  char format[] = "3,12";
1628  return invoke_function(fd, ID_COMMAND_PUTTAG, 2, format, hCommand, newVal);
1629 }
1630 
1631 HRESULT
1632 bCap_CommandGetID(int fd, uint32_t hCommand, VARIANT *pVal)
1633 {
1634  char format[] = "3:12";
1635  return invoke_function(fd, ID_COMMAND_GETID, 1, format, hCommand, pVal);
1636 }
1637 
1638 HRESULT
1639 bCap_CommandPutID(int fd, uint32_t hCommand, VARIANT newVal)
1640 {
1641  char format[] = "3,12";
1642  return invoke_function(fd, ID_COMMAND_PUTID, 2, format, hCommand, newVal);
1643 }
1644 
1645 HRESULT
1646 bCap_CommandRelease(int fd, uint32_t *hCommand)
1647 {
1648  char format[] = "3";
1649  HRESULT hr;
1650 
1651  if (hCommand == NULL)
1652  return E_INVALIDARG;
1653 
1654  hr = invoke_function(fd, ID_COMMAND_RELEASE, 1, format, *hCommand);
1655  if (SUCCEEDED(hr)) {
1656  *hCommand = 0;
1657  }
1658 
1659  return hr;
1660 }
1661 
1662 HRESULT
1663 bCap_MessageReply(int fd, uint32_t hMessage, VARIANT vntData)
1664 {
1665  char format[] = "3,12";
1666  return invoke_function(fd, ID_MESSAGE_REPLY, 2, format, hMessage, vntData);
1667 }
1668 
1669 HRESULT
1670 bCap_MessageClear(int fd, uint32_t hMessage)
1671 {
1672  char format[] = "3";
1673  return invoke_function(fd, ID_MESSAGE_CLEAR, 1, format, hMessage);
1674 }
1675 
1676 HRESULT
1677 bCap_MessageGetDateTime(int fd, uint32_t hMessage, VARIANT *pVal)
1678 {
1679  char format[] = "3:12";
1680  return invoke_function(fd, ID_MESSAGE_GETDATETIME, 1, format, hMessage, pVal);
1681 }
1682 
1683 HRESULT
1684 bCap_MessageGetDescription(int fd, uint32_t hMessage, BSTR *pVal)
1685 {
1686  char format[] = "3:8";
1687  return invoke_function(fd, ID_MESSAGE_GETDESCRIPTION, 1, format, hMessage,
1688  pVal);
1689 }
1690 
1691 HRESULT
1692 bCap_MessageGetDestination(int fd, uint32_t hMessage, BSTR *pVal)
1693 {
1694  char format[] = "3:8";
1695  return invoke_function(fd, ID_MESSAGE_GETDESTINATION, 1, format, hMessage,
1696  pVal);
1697 }
1698 
1699 HRESULT
1700 bCap_MessageGetNumber(int fd, uint32_t hMessage, int32_t *pVal)
1701 {
1702  char format[] = "3:3";
1703  return invoke_function(fd, ID_MESSAGE_GETNUMBER, 1, format, hMessage, pVal);
1704 }
1705 
1706 HRESULT
1708 {
1709  char format[] = "3:3";
1710  return invoke_function(fd, ID_MESSAGE_GETSERIALNUMBER, 1, format, hMessage,
1711  pVal);
1712 }
1713 
1714 HRESULT
1715 bCap_MessageGetSource(int fd, uint32_t hMessage, BSTR *pVal)
1716 {
1717  char format[] = "3:8";
1718  return invoke_function(fd, ID_MESSAGE_GETSOURCE, 1, format, hMessage, pVal);
1719 }
1720 
1721 HRESULT
1722 bCap_MessageGetValue(int fd, uint32_t hMessage, VARIANT *pVal)
1723 {
1724  char format[] = "3:12";
1725  return invoke_function(fd, ID_MESSAGE_GETVALUE, 1, format, hMessage, pVal);
1726 }
1727 
1728 HRESULT
1729 bCap_MessageRelease(int fd, uint32_t *hMessage)
1730 {
1731  char format[] = "3";
1732  HRESULT hr;
1733 
1734  if (hMessage == NULL)
1735  return E_INVALIDARG;
1736 
1737  hr = invoke_function(fd, ID_MESSAGE_RELEASE, 1, format, *hMessage);
1738  if (SUCCEEDED(hr)) {
1739  *hMessage = 0;
1740  }
1741 
1742  return hr;
1743 }
HRESULT bCap_CommandPutID(int fd, uint32_t hCommand, VARIANT newVal)
Send the b-CAP ID_COMMAND_PUTID packet.
Definition: bcap_client.c:1639
#define ID_MESSAGE_GETSOURCE
Definition: bcap_funcid.h:178
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
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
#define ID_FILE_GETHELP
Definition: bcap_funcid.h:93
HRESULT bCap_RobotHalt(int fd, uint32_t hRobot, BSTR bstrOption)
Send the b-CAP ID_ROBOT_HALT packet.
Definition: bcap_client.c:1199
_DN_EXP_THREAD HRESULT unlock_mutex(MUTEX *pmutex)
Unlocks mutex handle.
Definition: dn_thread.c:188
HRESULT bCap_CommandGetParameters(int fd, uint32_t hCommand, VARIANT *pVal)
Send the b-CAP ID_COMMAND_GETPARAMETERS packet.
Definition: bcap_client.c:1574
#define ID_COMMAND_GETATTRIBUTE
Definition: bcap_funcid.h:162
HRESULT bCap_TaskGetID(int fd, uint32_t hTask, VARIANT *pVal)
Send the b-CAP ID_TASK_GETID packet.
Definition: bcap_client.c:1410
b-CAP client communication object.
Definition: bcap_client.c:66
#define ID_TASK_GETVARIABLE
Definition: bcap_funcid.h:125
HRESULT bCap_FilePutValue(int fd, uint32_t hFile, VARIANT newVal)
Send the b-CAP ID_FILE_PUTVALUE packet.
Definition: bcap_client.c:1058
HRESULT bCap_ControllerGetAttribute(int fd, uint32_t hController, int32_t *pVal)
Send the b-CAP ID_CONTROLLER_GETATTRIBUTE packet.
Definition: bcap_client.c:779
HRESULT bCap_VariableGetAttribute(int fd, uint32_t hVariable, int32_t *pVal)
Send the b-CAP ID_VARIABLE_GETATTRIBUTE packet.
Definition: bcap_client.c:1463
#define ID_VARIABLE_GETVALUE
Definition: bcap_funcid.h:142
#define ID_FILE_RELEASE
Definition: bcap_funcid.h:99
#define ID_CONTROLLER_GETROBOTNAMES
Definition: bcap_funcid.h:49
TCP API file.
unsigned uint32_t
Definition: stdint.h:43
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_COMMON HRESULT bcap_recv(struct CONN_PARAM_COMMON *device, struct BCAP_PACKET *packet_recv, int client)
Receives b-CAP packet.
Definition: bcap_common.c:984
#define S_EXECUTING
Succeeded but the server has been executing yet.
Definition: bcap_common.h:63
struct CONN_PARAM_COMMON device
Definition: bcap_client.c:68
HRESULT bCap_MessageClear(int fd, uint32_t hMessage)
Send the b-CAP ID_MESSAGE_CLEAR packet.
Definition: bcap_client.c:1670
#define ID_CONTROLLER_EXECUTE
Definition: bcap_funcid.h:53
uint16_t argc
Definition: bcap_common.h:232
HRESULT bCap_FilePutTag(int fd, uint32_t hFile, VARIANT newVal)
Send the b-CAP ID_FILE_PUTTAG packet.
Definition: bcap_client.c:1093
HRESULT bCap_ExtensionGetTag(int fd, uint32_t hExtension, VARIANT *pVal)
Send the b-CAP ID_EXTENSION_GETTAG packet.
Definition: bcap_client.c:884
HRESULT(* dn_set_timeout)(int sock, uint32_t timeout)
Definition: dn_device.h:181
HRESULT bCap_CommandGetID(int fd, uint32_t hCommand, VARIANT *pVal)
Send the b-CAP ID_COMMAND_GETID packet.
Definition: bcap_client.c:1632
#define ID_FILE_GETTAG
Definition: bcap_funcid.h:95
#define ID_FILE_RUN
Definition: bcap_funcid.h:83
UDP API file.
HRESULT bCap_MessageGetSource(int fd, uint32_t hMessage, BSTR *pVal)
Send the b-CAP ID_MESSAGE_GETSOURCE packet.
Definition: bcap_client.c:1715
#define ID_ROBOT_DRIVE
Definition: bcap_funcid.h:107
HRESULT bCap_RobotPutTag(int fd, uint32_t hRobot, VARIANT newVal)
Send the b-CAP ID_ROBOT_PUTTAG packet.
Definition: bcap_client.c:1280
#define ID_FILE_GETTYPE
Definition: bcap_funcid.h:89
static HRESULT send_receive(int index, struct BCAP_PACKET *packet_send, struct BCAP_PACKET *packet_recv)
Sends and receives the b-CAP packet.
Definition: bcap_client.c:125
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
HRESULT bCap_SetTimeout(int fd, uint32_t timeout)
Sets timeout.
Definition: bcap_client.c:486
HRESULT bCap_RobotGoHome(int fd, uint32_t hRobot)
Send the b-CAP ID_ROBOT_GOHOME packet.
Definition: bcap_client.c:1192
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
#define ID_CONTROLLER_PUTTAG
Definition: bcap_funcid.h:59
#define ID_EXTENSION_PUTID
Definition: bcap_funcid.h:72
#define ID_FILE_GETDATELASTMODIFIED
Definition: bcap_funcid.h:86
HRESULT bCap_VariableRelease(int fd, uint32_t *hVariable)
Send the b-CAP ID_VARIABLE_RELEASE packet.
Definition: bcap_client.c:1521
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
uint32_t timeout
Definition: dn_device.h:174
HRESULT bCap_VariablePutValue(int fd, uint32_t hVariable, VARIANT newVal)
Send the b-CAP ID_VARIABLE_PUTVALUE packet.
Definition: bcap_client.c:1456
HRESULT(* dn_recv)(int sock, char *buf, uint32_t len_buf, uint32_t *len_recved, uint32_t timeout, void *arg)
Definition: dn_device.h:179
#define ID_TASK_GETVARIABLENAMES
Definition: bcap_funcid.h:126
HRESULT bCap_VariableGetMicrosecond(int fd, uint32_t hVariable, int32_t *pVal)
Send the b-CAP ID_VARIABLE_GETMICROSECOND packet.
Definition: bcap_client.c:1513
#define ID_CONTROLLER_CONNECT
Definition: bcap_funcid.h:39
HRESULT bCap_FileGetDateLastModified(int fd, uint32_t hFile, VARIANT *pVal)
Send the b-CAP ID_FILE_GETDATELASTMODIFIED packet.
Definition: bcap_client.c:1022
#define ID_EXTENSION_GETID
Definition: bcap_funcid.h:71
HRESULT bCap_ExtensionPutID(int fd, uint32_t hExtension, VARIANT newVal)
Send the b-CAP ID_EXTENSION_PUTID packet.
Definition: bcap_client.c:905
#define ID_TASK_DELETE
Definition: bcap_funcid.h:130
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
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
#define S_OK
Succeeded.
Definition: dn_common.h:89
#define ID_COMMAND_PUTID
Definition: bcap_funcid.h:168
HRESULT bCap_ExtensionGetHelp(int fd, uint32_t hExtension, BSTR *pVal)
Send the b-CAP ID_EXTENSION_GETHELP packet.
Definition: bcap_client.c:870
_DN_EXP_THREAD HRESULT lock_mutex(MUTEX *pmutex, uint32_t timeout)
Locks mutex handle.
Definition: dn_thread.c:145
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
HRESULT bCap_FileGetHelp(int fd, uint32_t hFile, BSTR *pVal)
Send the b-CAP ID_FILE_GETHELP packet.
Definition: bcap_client.c:1072
#define ID_EXTENSION_GETATTRIBUTE
Definition: bcap_funcid.h:66
#define ID_FILE_GETFILENAMES
Definition: bcap_funcid.h:77
#define ID_ROBOT_GETTAG
Definition: bcap_funcid.h:119
#define _RETRY_MAX
A definition for the maximum retry count.
Definition: bcap_client.c:60
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
HRESULT bCap_MessageReply(int fd, uint32_t hMessage, VARIANT vntData)
Send the b-CAP ID_MESSAGE_REPLY packet.
Definition: bcap_client.c:1663
HRESULT bCap_TaskGetTag(int fd, uint32_t hTask, VARIANT *pVal)
Send the b-CAP ID_TASK_GETTAG packet.
Definition: bcap_client.c:1396
static struct CONN_BCAP_CLIENT * check_address(int index)
Checks whether the index has been used or not.
Definition: bcap_client.c:103
wchar_t * BSTR
Definition: dn_common.h:239
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
HRESULT bCap_ServiceStop(int fd)
Send the b-CAP ID_SERVICE_STOP packet.
Definition: bcap_client.c:605
#define ID_FILE_PUTID
Definition: bcap_funcid.h:98
#define _RETRY_MIN
A definition for the minimum retry count.
Definition: bcap_client.c:54
HRESULT bCap_FileGetType(int fd, uint32_t hFile, BSTR *pVal)
Send the b-CAP ID_FILE_GETTYPE packet.
Definition: bcap_client.c:1044
#define ID_MESSAGE_GETDATETIME
Definition: bcap_funcid.h:173
unsigned short uint16_t
Definition: stdint.h:41
HRESULT bCap_RobotGetAttribute(int fd, uint32_t hRobot, int32_t *pVal)
Send the b-CAP ID_ROBOT_GETATTRIBUTE packet.
Definition: bcap_client.c:1252
#define ID_TASK_STOP
Definition: bcap_funcid.h:129
_DN_EXP_UDP HRESULT udp_send(int sock, const char *buf, uint32_t len_buf, void *arg)
Sends UDP packet.
Definition: dn_udp.c:94
HRESULT bCap_CommandGetTimeout(int fd, uint32_t hCommand, int32_t *pVal)
Send the b-CAP ID_COMMAND_GETTIMEOUT packet.
Definition: bcap_client.c:1553
#define BCAP_CONN_MAX
A definition for the maximum count of b-CAP client connections.
Definition: bcap_client.h:47
HRESULT bCap_CommandGetName(int fd, uint32_t hCommand, BSTR *pVal)
Send the b-CAP ID_COMMAND_GETNAME packet.
Definition: bcap_client.c:1611
#define ID_MESSAGE_GETVALUE
Definition: bcap_funcid.h:179
#define ID_ROBOT_ROTATE
Definition: bcap_funcid.h:112
HRESULT bCap_FileGetTag(int fd, uint32_t hFile, VARIANT *pVal)
Send the b-CAP ID_FILE_GETTAG packet.
Definition: bcap_client.c:1086
#define ID_VARIABLE_GETHELP
Definition: bcap_funcid.h:145
#define ID_ROBOT_EXECUTE
Definition: bcap_funcid.h:103
int32_t lVal
Definition: dn_common.h:312
HRESULT bCap_TaskGetName(int fd, uint32_t hTask, BSTR *pVal)
Send the b-CAP ID_TASK_GETNAME packet.
Definition: bcap_client.c:1389
#define ID_ROBOT_UNCHUCK
Definition: bcap_funcid.h:114
#define ID_EXTENSION_PUTTAG
Definition: bcap_funcid.h:70
VARIANT * args
Definition: bcap_common.h:233
HRESULT bCap_RobotPutID(int fd, uint32_t hRobot, VARIANT newVal)
Send the b-CAP ID_ROBOT_PUTID packet.
Definition: bcap_client.c:1294
HRESULT bCap_RobotGetName(int fd, uint32_t hRobot, BSTR *pVal)
Send the b-CAP ID_ROBOT_GETNAME packet.
Definition: bcap_client.c:1266
b-CAP Function ID file.
#define ID_VARIABLE_RELEASE
Definition: bcap_funcid.h:152
#define ID_ROBOT_GETATTRIBUTE
Definition: bcap_funcid.h:116
BSTR bstrVal
Definition: dn_common.h:318
HRESULT bCap_RobotRelease(int fd, uint32_t *hRobot)
Send the b-CAP ID_ROBOT_RELEASE packet.
Definition: bcap_client.c:1301
Thread and mutex API file.
#define ID_TASK_RELEASE
Definition: bcap_funcid.h:139
#define ID_ROBOT_UNHOLD
Definition: bcap_funcid.h:115
HRESULT bCap_FileGetDateCreated(int fd, uint32_t hFile, VARIANT *pVal)
Send the b-CAP ID_FILE_GETDATECREATED packet.
Definition: bcap_client.c:1007
HRESULT bCap_Open_Client(const char *connect, uint32_t timeout, unsigned int retry, int *pfd)
Starts b-CAP communication.
Definition: bcap_client.c:322
#define ID_FILE_GETVARIABLENAMES
Definition: bcap_funcid.h:78
#define ID_FILE_EXECUTE
Definition: bcap_funcid.h:79
#define FAILED(hr)
A macro that returns TRUE/FALSE. If hr is less than zero, then returns TRUE.
Definition: dn_common.h:77
#define ID_VARIABLE_GETNAME
Definition: bcap_funcid.h:146
#define ID_CONTROLLER_GETMESSAGE
Definition: bcap_funcid.h:54
_DN_EXP_COM HRESULT com_open(void *param, int *sock)
Opens serial port.
Definition: dn_com.c:360
#define ID_TASK_GETID
Definition: bcap_funcid.h:137
#define ID_TASK_GETFILENAME
Definition: bcap_funcid.h:131
HRESULT bCap_SetRetry(int fd, unsigned int retry)
Sets retry count.
Definition: bcap_client.c:536
#define ID_MESSAGE_CLEAR
Definition: bcap_funcid.h:172
HRESULT bCap_ControllerGetID(int fd, uint32_t hController, VARIANT *pVal)
Send the b-CAP ID_CONTROLLER_GETID packet.
Definition: bcap_client.c:818
HRESULT bCap_MessageGetValue(int fd, uint32_t hMessage, VARIANT *pVal)
Send the b-CAP ID_MESSAGE_GETVALUE packet.
Definition: bcap_client.c:1722
#define E_HANDLE
Failed because the handle is invalid.
Definition: dn_common.h:119
HRESULT bCap_CommandGetHelp(int fd, uint32_t hCommand, BSTR *pVal)
Send the b-CAP ID_COMMAND_GETHELP packet.
Definition: bcap_client.c:1604
HRESULT bCap_TaskPutTag(int fd, uint32_t hTask, VARIANT newVal)
Send the b-CAP ID_TASK_PUTTAG packet.
Definition: bcap_client.c:1403
_DN_EXP_UDP HRESULT udp_set_timeout(int sock, uint32_t timeout)
Sets timeout value to the UDP socket.
Definition: dn_udp.c:173
HRESULT bCap_TaskGetHelp(int fd, uint32_t hTask, BSTR *pVal)
Send the b-CAP ID_TASK_GETHELP packet.
Definition: bcap_client.c:1382
HRESULT bCap_RobotUnchuck(int fd, uint32_t hRobot, BSTR bstrOption)
Send the b-CAP ID_ROBOT_UNCHUCK packet.
Definition: bcap_client.c:1238
#define ID_CONTROLLER_DISCONNECT
Definition: bcap_funcid.h:40
#define ID_COMMAND_GETSTATE
Definition: bcap_funcid.h:158
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
#define ID_TASK_PUTTAG
Definition: bcap_funcid.h:136
#define ID_MESSAGE_RELEASE
Definition: bcap_funcid.h:180
#define E_INVALIDARG
Failed because some arguments are invalid.
Definition: dn_common.h:131
HRESULT(* dn_close)(int *sock)
Definition: dn_device.h:177
int MUTEX
#define ID_ROBOT_HOLD
Definition: bcap_funcid.h:110
#define ID_COMMAND_GETPARAMETERS
Definition: bcap_funcid.h:159
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
HRESULT bCap_CommandCancel(int fd, uint32_t hCommand)
Send the b-CAP ID_COMMAND_CANCEL packet.
Definition: bcap_client.c:1546
HRESULT bCap_ControllerGetMessage(int fd, uint32_t hController, uint32_t *hMessage)
Send the b-CAP ID_CONTROLLER_GETMESSAGE packet.
Definition: bcap_client.c:769
#define ID_EXTENSION_GETVARIABLE
Definition: bcap_funcid.h:63
HRESULT bCap_VariableGetTag(int fd, uint32_t hVariable, VARIANT *pVal)
Send the b-CAP ID_VARIABLE_GETTAG packet.
Definition: bcap_client.c:1485
#define ID_TASK_PUTID
Definition: bcap_funcid.h:138
HRESULT bCap_FileGetID(int fd, uint32_t hFile, VARIANT *pVal)
Send the b-CAP ID_FILE_GETID packet.
Definition: bcap_client.c:1100
HRESULT bCap_FileGetAttribute(int fd, uint32_t hFile, int32_t *pVal)
Send the b-CAP ID_FILE_GETATTRIBUTE packet.
Definition: bcap_client.c:1065
HRESULT bCap_TaskPutID(int fd, uint32_t hTask, VARIANT newVal)
Send the b-CAP ID_TASK_PUTID packet.
Definition: bcap_client.c:1417
#define ID_FILE_GETVALUE
Definition: bcap_funcid.h:90
#define ID_FILE_PUTTAG
Definition: bcap_funcid.h:96
_DN_EXP_COM HRESULT com_set_timeout(int sock, uint32_t timeout)
Sets timeout value to the serial socket.
Definition: dn_com.c:489
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
HRESULT bCap_VariablePutID(int fd, uint32_t hVariable, VARIANT newVal)
Send the b-CAP ID_VARIABLE_PUTID packet.
Definition: bcap_client.c:1506
_DN_EXP_DEVICE HRESULT parse_conn_param_serial(const char *opt, struct CONN_PARAM_COM *param)
Parses serial connection parameters.
Definition: dn_device.c:235
#define ID_EXTENSION_RELEASE
Definition: bcap_funcid.h:73
#define ID_ROBOT_ACCELERATE
Definition: bcap_funcid.h:104
static struct CONN_BCAP_CLIENT m_conn_param[BCAP_CONN_MAX]
Definition: bcap_client.c:74
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
#define ID_VARIABLE_GETMICROSECOND
Definition: bcap_funcid.h:151
HRESULT bCap_FileGetName(int fd, uint32_t hFile, BSTR *pVal)
Send the b-CAP ID_FILE_GETNAME packet.
Definition: bcap_client.c:1079
#define ID_FILE_GETNAME
Definition: bcap_funcid.h:94
#define ID_TASK_GETTAG
Definition: bcap_funcid.h:135
#define ID_FILE_GETID
Definition: bcap_funcid.h:97
HRESULT bCap_RobotChuck(int fd, uint32_t hRobot, BSTR bstrOption)
Send the b-CAP ID_ROBOT_CHUCK packet.
Definition: bcap_client.c:1176
_DN_EXP_COM HRESULT com_recv(int sock, char *buf, uint32_t len_buf, uint32_t *len_recved, uint32_t timeout, void *arg)
Receives serial packet.
Definition: dn_com.c:453
HRESULT bCap_ServiceStart(int fd, BSTR bstrOption)
Send the b-CAP ID_SERVICE_START packet.
Definition: bcap_client.c:598
HRESULT bCap_RobotUnhold(int fd, uint32_t hRobot, BSTR bstrOption)
Send the b-CAP ID_ROBOT_UNHOLD packet.
Definition: bcap_client.c:1245
HRESULT bCap_RobotGetHelp(int fd, uint32_t hRobot, BSTR *pVal)
Send the b-CAP ID_ROBOT_GETHELP packet.
Definition: bcap_client.c:1259
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
HRESULT bCap_ControllerGetHelp(int fd, uint32_t hController, BSTR *pVal)
Send the b-CAP ID_CONTROLLER_GETHELP packet.
Definition: bcap_client.c:787
_DN_EXP_UDP HRESULT udp_open(void *param, int *sock)
Opens UDP socket.
Definition: dn_udp.c:52
#define E_FAIL
Failed because unspecified error occurs.
Definition: dn_common.h:107
#define ID_CONTROLLER_GETFILENAMES
Definition: bcap_funcid.h:48
int32_t HRESULT
Definition: dn_common.h:61
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
#define ID_COMMAND_GETRESULT
Definition: bcap_funcid.h:161
HRESULT bCap_ExtensionRelease(int fd, uint32_t *hExtension)
Send the b-CAP ID_EXTENSION_RELEASE packet.
Definition: bcap_client.c:912
static uint32_t inet_addr(const char *addr)
#define ID_VARIABLE_GETATTRIBUTE
Definition: bcap_funcid.h:144
HRESULT bCap_TaskRelease(int fd, uint32_t *hTask)
Send the b-CAP ID_TASK_RELEASE packet.
Definition: bcap_client.c:1424
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
#define ID_CONTROLLER_GETCOMMAND
Definition: bcap_funcid.h:46
#define ID_FILE_GETFILE
Definition: bcap_funcid.h:75
#define ID_TASK_START
Definition: bcap_funcid.h:128
HRESULT bCap_VariableGetName(int fd, uint32_t hVariable, BSTR *pVal)
Send the b-CAP ID_VARIABLE_GETNAME packet.
Definition: bcap_client.c:1478
int32_t id
Definition: bcap_common.h:231
#define ID_VARIABLE_GETDATETIME
Definition: bcap_funcid.h:141
#define ID_MESSAGE_GETSERIALNUMBER
Definition: bcap_funcid.h:177
#define ID_COMMAND_GETTIMEOUT
Definition: bcap_funcid.h:156
HRESULT bCap_MessageRelease(int fd, uint32_t *hMessage)
Send the b-CAP ID_MESSAGE_RELEASE packet.
Definition: bcap_client.c:1729
HRESULT bCap_CommandPutParameters(int fd, uint32_t hCommand, VARIANT newVal)
Send the b-CAP ID_VARIABLE_PUTPARAMETERS packet.
Definition: bcap_client.c:1582
#define ID_MESSAGE_REPLY
Definition: bcap_funcid.h:171
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
#define ID_CONTROLLER_PUTID
Definition: bcap_funcid.h:61
_DN_EXP_COM HRESULT com_close(int *sock)
Closes the socket.
Definition: dn_com.c:385
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
#define ID_CONTROLLER_GETTAG
Definition: bcap_funcid.h:58
#define E_OUTOFMEMORY
Failed because there is no enough memory space.
Definition: dn_common.h:125
uint16_t sin_port
uint16_t serial
Definition: bcap_client.c:70
HRESULT bCap_VariablePutTag(int fd, uint32_t hVariable, VARIANT newVal)
Send the b-CAP ID_VARIABLE_PUTTAG packet.
Definition: bcap_client.c:1492
#define ID_TASK_GETATTRIBUTE
Definition: bcap_funcid.h:132
uint16_t reserv
Definition: bcap_common.h:230
HRESULT bCap_ControllerPutID(int fd, uint32_t hController, VARIANT newVal)
Send the b-CAP ID_CONTROLLER_PUTID packet.
Definition: bcap_client.c:825
#define ID_ROBOT_GETHELP
Definition: bcap_funcid.h:117
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
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
HRESULT bCap_FilePutID(int fd, uint32_t hFile, VARIANT newVal)
Send the b-CAP ID_FILE_PUTID packet.
Definition: bcap_client.c:1107
#define ID_ROBOT_GETVARIABLENAMES
Definition: bcap_funcid.h:102
#define ID_MESSAGE_GETDESCRIPTION
Definition: bcap_funcid.h:174
#define NOPARITY
A definition for serial communication setting.
Definition: dn_device.h:69
#define AF_INET
Definition: dn_additional.h:66
HRESULT bCap_CommandGetState(int fd, uint32_t hCommand, int32_t *pVal)
Send the b-CAP ID_COMMAND_GETSTATE packet.
Definition: bcap_client.c:1567
#define ID_ROBOT_PUTID
Definition: bcap_funcid.h:122
HRESULT bCap_VariableGetID(int fd, uint32_t hVariable, VARIANT *pVal)
Send the b-CAP ID_VARIABLE_GETID packet.
Definition: bcap_client.c:1499
_DN_EXP_UDP HRESULT udp_recv(int sock, char *buf, uint32_t len_buf, uint32_t *len_recved, uint32_t timeout, void *arg)
Receives UDP packet.
Definition: dn_udp.c:135
#define SUCCEEDED(hr)
A macro that returns TRUE/FALSE. If hr is zero or more, then returns TRUE.
Definition: dn_common.h:71
b-CAP Client API file.
HRESULT bCap_FileDelete(int fd, uint32_t hFile, BSTR bstrOption)
Send the b-CAP ID_FILE_DELETE packet.
Definition: bcap_client.c:985
#define ID_COMMAND_GETNAME
Definition: bcap_funcid.h:164
HRESULT bCap_ControllerGetName(int fd, uint32_t hController, BSTR *pVal)
Send the b-CAP ID_CONTROLLER_GETNAME packet.
Definition: bcap_client.c:795
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
A type definition for Ethernet connection parameters.
Definition: dn_device.h:144
Common device API file.
HRESULT bCap_ControllerGetTag(int fd, uint32_t hController, VARIANT *pVal)
Send the b-CAP ID_CONTROLLER_GETTAG packet.
Definition: bcap_client.c:803
uint16_t vt
Definition: dn_common.h:308
#define ID_EXTENSION_GETNAME
Definition: bcap_funcid.h:68
#define ONESTOPBIT
A definition for serial communication setting.
Definition: dn_device.h:87
Common API file.
HRESULT bCap_VariableGetHelp(int fd, uint32_t hVariable, BSTR *pVal)
Send the b-CAP ID_VARIABLE_GETHELP packet.
Definition: bcap_client.c:1471
#define ID_VARIABLE_PUTTAG
Definition: bcap_funcid.h:148
#define ID_ROBOT_GETVARIABLE
Definition: bcap_funcid.h:101
HRESULT bCap_CommandGetTag(int fd, uint32_t hCommand, VARIANT *pVal)
Send the b-CAP ID_COMMAND_GETTAG packet.
Definition: bcap_client.c:1618
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
#define INFINITE
A definition for infinite wait.
Definition: dn_thread.h:95
_DN_EXP_COMMON void VariantInit(VARIANT *pvarg)
Initializes the VARIANT.
Definition: dn_common.c:368
#define ID_ROBOT_GETNAME
Definition: bcap_funcid.h:118
HRESULT bCap_CommandGetAttribute(int fd, uint32_t hCommand, int32_t *pVal)
Send the b-CAP ID_COMMAND_GETATTRIBUTE packet.
Definition: bcap_client.c:1597
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
static HRESULT invoke_function(int fd, int32_t id, int argc, char *format,...)
Definition: bcap_client.c:196
HRESULT bCap_ExtensionGetAttribute(int fd, uint32_t hExtension, int32_t *pVal)
Send the b-CAP ID_EXTENSION_GETATTRIBUTE packet.
Definition: bcap_client.c:862
#define ID_CONTROLLER_GETTASKNAMES
Definition: bcap_funcid.h:50
_DN_EXP_TCP HRESULT tcp_recv(int sock, char *buf, uint32_t len_buf, uint32_t *len_recved, uint32_t timeout, void *arg)
Receives TCP packet.
Definition: dn_tcp.c:364
A type definition for common communication parameters.
Definition: dn_device.h:170
User own API file.
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
static uint16_t htons(uint16_t hostshort)
#define ID_VARIABLE_PUTVALUE
Definition: bcap_funcid.h:143
#define ID_ROBOT_CHANGE
Definition: bcap_funcid.h:105
#define ID_FILE_MOVE
Definition: bcap_funcid.h:82
#define ID_FILE_GETDATELASTACCESSED
Definition: bcap_funcid.h:85
#define ID_COMMAND_RELEASE
Definition: bcap_funcid.h:169
#define ID_FILE_GETSIZE
Definition: bcap_funcid.h:88
HRESULT(* dn_open)(void *param, int *sock)
Definition: dn_device.h:176
#define ID_ROBOT_SPEED
Definition: bcap_funcid.h:113
_DN_EXP_COM HRESULT com_send(int sock, const char *buf, uint32_t len_buf, void *arg)
Sends serial packet.
Definition: dn_com.c:412
HRESULT bCap_CommandGetResult(int fd, uint32_t hCommand, VARIANT *pVal)
Send the b-CAP ID_COMMAND_GETRESULT packet.
Definition: bcap_client.c:1590
HRESULT bCap_RobotHold(int fd, uint32_t hRobot, BSTR bstrOption)
Send the b-CAP ID_ROBOT_HOLD packet.
Definition: bcap_client.c:1206
struct in_addr sin_addr
#define ID_FILE_GETDATECREATED
Definition: bcap_funcid.h:84
#define ID_FILE_GETPATH
Definition: bcap_funcid.h:87
A type definition for the multi type variable.
Definition: dn_common.h:306
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
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
#define ID_FILE_PUTVALUE
Definition: bcap_funcid.h:91
_DN_EXP_COMMON BSTR SysAllocString(const wchar_t *sz)
Allocates and returns BSTR.
Definition: dn_common.c:61
#define ID_ROBOT_PUTTAG
Definition: bcap_funcid.h:120
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
_DN_EXP_THREAD HRESULT release_mutex(MUTEX *pmutex)
Releases mutex handle.
Definition: dn_thread.c:108
#define ID_CONTROLLER_GETNAME
Definition: bcap_funcid.h:57
#define ID_EXTENSION_GETTAG
Definition: bcap_funcid.h:69
#define E_MAX_OBJECT
Failed because the packet is too much.
Definition: dn_common.h:181
_DN_EXP_COMMON void VariantClear(VARIANT *pvarg)
Clears the VARIANT.
Definition: dn_common.c:382
HRESULT bCap_CommandRelease(int fd, uint32_t *hCommand)
Send the b-CAP ID_COMMAND_RELEASE packet.
Definition: bcap_client.c:1646
uint16_t dst_port
Definition: dn_device.h:147
int int32_t
Definition: stdint.h:42
HRESULT bCap_CommandPutTag(int fd, uint32_t hCommand, VARIANT newVal)
Send the b-CAP ID_COMMAND_PUTTAG packet.
Definition: bcap_client.c:1625
HRESULT bCap_VariableGetValue(int fd, uint32_t hVariable, VARIANT *pVal)
Send the b-CAP ID_VARIABLE_GETVALUE packet.
Definition: bcap_client.c:1449
_DN_EXP_DEVICE int parse_conn_type(const char *opt)
Parses and returns the connection type.
Definition: dn_device.c:93
A type definition for the b-CAP packet.
Definition: bcap_common.h:227
HRESULT bCap_MessageGetSerialNumber(int fd, uint32_t hMessage, int32_t *pVal)
Send the b-CAP ID_MESSAGE_GETSERIALNUMBER packet.
Definition: bcap_client.c:1707
#define ID_FILE_DELETE
Definition: bcap_funcid.h:81
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
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
HRESULT bCap_Close_Client(int *pfd)
Ends b-CAP communication.
Definition: bcap_client.c:447
#define ID_MESSAGE_GETNUMBER
Definition: bcap_funcid.h:176
A type definition for serial connection parameters.
Definition: dn_device.h:156
#define ID_TASK_GETHELP
Definition: bcap_funcid.h:133
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
#define ID_CONTROLLER_GETEXTENSION
Definition: bcap_funcid.h:41
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
#define ID_CONTROLLER_GETHELP
Definition: bcap_funcid.h:56
HRESULT bCap_GetRetry(int fd, unsigned int *retry)
Gets retry count.
Definition: bcap_client.c:581
#define ID_MESSAGE_GETDESTINATION
Definition: bcap_funcid.h:175
HRESULT bCap_GetTimeout(int fd, uint32_t *timeout)
Gets timeout.
Definition: bcap_client.c:517
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
HRESULT bCap_FileGetPath(int fd, uint32_t hFile, BSTR *pVal)
Send the b-CAP ID_FILE_GETPATH packet.
Definition: bcap_client.c:1030
#define ID_COMMAND_PUTTIMEOUT
Definition: bcap_funcid.h:157
_DN_EXP_TCP HRESULT tcp_set_timeout(int sock, uint32_t timeout)
Sets timeout value to the TCP socket.
Definition: dn_tcp.c:405
HRESULT bCap_TaskDelete(int fd, uint32_t hTask, BSTR bstrOption)
Send the b-CAP ID_TASK_DELETE packet.
Definition: bcap_client.c:1361
#define ID_COMMAND_GETTAG
Definition: bcap_funcid.h:165
#define ID_CONTROLLER_GETTASK
Definition: bcap_funcid.h:44
#define ID_CONTROLLER_GETROBOT
Definition: bcap_funcid.h:43
_DN_EXP_TCP HRESULT tcp_send(int sock, const char *buf, uint32_t len_buf, void *arg)
Sends TCP packet.
Definition: dn_tcp.c:319
HRESULT bCap_RobotChange(int fd, uint32_t hRobot, BSTR bstrName)
Send the b-CAP ID_ROBOT_CHANGE packet.
Definition: bcap_client.c:1169
#define ID_EXTENSION_GETHELP
Definition: bcap_funcid.h:67
uint32_t tcp_conn_timeout
Definition: dn_tcp.c:47
#define ID_ROBOT_MOVE
Definition: bcap_funcid.h:111
static int find_open_address()
Returns the open address of m_conn_param.
Definition: bcap_client.c:82
HRESULT bCap_TaskGetAttribute(int fd, uint32_t hTask, int32_t *pVal)
Send the b-CAP ID_TASK_GETATTRIBUTE packet.
Definition: bcap_client.c:1375
HRESULT bCap_CommandPutTimeout(int fd, uint32_t hCommand, int32_t newVal)
Send the b-CAP ID_COMMAND_PUTTIMEOUT packet.
Definition: bcap_client.c:1560
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
#define ID_COMMAND_GETID
Definition: bcap_funcid.h:167
#define ID_CONTROLLER_GETATTRIBUTE
Definition: bcap_funcid.h:55
float fltVal
Definition: dn_common.h:314
HRESULT bCap_ControllerPutTag(int fd, uint32_t hController, VARIANT newVal)
Send the b-CAP ID_CONTROLLER_PUTTAG packet.
Definition: bcap_client.c:810
#define ID_EXTENSION_EXECUTE
Definition: bcap_funcid.h:65
#define ID_CONTROLLER_GETVARIABLENAMES
Definition: bcap_funcid.h:51
#define ID_SERVICE_STOP
Definition: bcap_funcid.h:37
#define ID_ROBOT_HALT
Definition: bcap_funcid.h:109
#define ID_CONTROLLER_GETCOMMANDNAMES
Definition: bcap_funcid.h:52
#define ID_VARIABLE_GETTAG
Definition: bcap_funcid.h:147
Serial API file.
#define ID_COMMAND_CANCEL
Definition: bcap_funcid.h:155
HRESULT bCap_FileGetValue(int fd, uint32_t hFile, VARIANT *pVal)
Send the b-CAP ID_FILE_GETVALUE packet.
Definition: bcap_client.c:1051
#define ID_TASK_EXECUTE
Definition: bcap_funcid.h:127
unsigned int retry
Definition: bcap_client.c:69
#define ID_CONTROLLER_GETFILE
Definition: bcap_funcid.h:42
#define ID_COMMAND_GETHELP
Definition: bcap_funcid.h:163
#define ID_ROBOT_CHUCK
Definition: bcap_funcid.h:106
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
#define ID_COMMAND_PUTPARAMETERS
Definition: bcap_funcid.h:160
_DN_EXP_UDP HRESULT udp_close(int *sock)
Closes the socket.
Definition: dn_udp.c:80
#define ID_FILE_COPY
Definition: bcap_funcid.h:80
HRESULT bCap_MessageGetDescription(int fd, uint32_t hMessage, BSTR *pVal)
Send the b-CAP ID_MESSAGE_GETDESCRIPTION packet.
Definition: bcap_client.c:1684
HRESULT bCap_ExtensionGetID(int fd, uint32_t hExtension, VARIANT *pVal)
Send the b-CAP ID_EXTENSION_GETID packet.
Definition: bcap_client.c:898
HRESULT bCap_MessageGetNumber(int fd, uint32_t hMessage, int32_t *pVal)
Send the b-CAP ID_MESSAGE_GETNUMBER packet.
Definition: bcap_client.c:1700
_DN_EXP_TCP HRESULT tcp_close(int *sock)
Closes the socket.
Definition: dn_tcp.c:305
#define ID_ROBOT_GETID
Definition: bcap_funcid.h:121
b-CAP Common API file.
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
#define ID_TASK_GETNAME
Definition: bcap_funcid.h:134
#define ID_FILE_GETVARIABLE
Definition: bcap_funcid.h:76
uint32_t dst_addr
Definition: dn_device.h:146
#define ID_CONTROLLER_GETID
Definition: bcap_funcid.h:60
#define ID_FILE_GETATTRIBUTE
Definition: bcap_funcid.h:92
#define ID_COMMAND_PUTTAG
Definition: bcap_funcid.h:166
_DN_EXP_TCP HRESULT tcp_open_client(void *param, int *sock)
Opens TCP client.
Definition: dn_tcp.c:107
static int connect(SOCKET s, const struct sockaddr *name, int namelen)
HRESULT bCap_FileGetDateLastAccessed(int fd, uint32_t hFile, VARIANT *pVal)
Send the b-CAP ID_FILE_GETDATELASTACCESSED packet.
Definition: bcap_client.c:1014
HRESULT(* dn_send)(int sock, const char *buf, uint32_t len_buf, void *arg)
Definition: dn_device.h:178
#define ID_SERVICE_START
Definition: bcap_funcid.h:36
_BCAP_EXP_COMMON HRESULT bcap_send(struct CONN_PARAM_COMMON *device, struct BCAP_PACKET *packet_send)
Sends b-CAP packet.
Definition: bcap_common.c:899
_DN_EXP_DEVICE HRESULT parse_conn_param_ether(const char *opt, struct CONN_PARAM_ETH *param)
Parses Ethernet connection parameters.
Definition: dn_device.c:121
HRESULT bCap_ControllerDisconnect(int fd, uint32_t *hController)
Send the b-CAP ID_CONTROLLER_DISCONNECT packet.
Definition: bcap_client.c:623
HRESULT bCap_MessageGetDestination(int fd, uint32_t hMessage, BSTR *pVal)
Send the b-CAP ID_MESSAGE_GETDESTINATION packet.
Definition: bcap_client.c:1692
_DN_EXP_THREAD HRESULT initialize_mutex(MUTEX *pmutex)
Initializes mutex handle.
Definition: dn_thread.c:80
HRESULT bCap_VariableGetDateTime(int fd, uint32_t hVariable, VARIANT *pVal)
Send the b-CAP ID_VARIABLE_GETDATETIME packet.
Definition: bcap_client.c:1441
HRESULT bCap_ExtensionGetName(int fd, uint32_t hExtension, BSTR *pVal)
Send the b-CAP ID_EXTENSION_GETNAME packet.
Definition: bcap_client.c:877
short sin_family
HRESULT bCap_MessageGetDateTime(int fd, uint32_t hMessage, VARIANT *pVal)
Send the b-CAP ID_MESSAGE_GETDATETIME packet.
Definition: bcap_client.c:1677
#define ID_CONTROLLER_GETEXTENSIONNAMES
Definition: bcap_funcid.h:47
HRESULT bCap_FileRelease(int fd, uint32_t *hFile)
Send the b-CAP ID_FILE_RELEASE packet.
Definition: bcap_client.c:1114
uint16_t serial
Definition: bcap_common.h:229
#define ID_VARIABLE_GETID
Definition: bcap_funcid.h:149
#define ID_EXTENSION_GETVARIABLENAMES
Definition: bcap_funcid.h:64
HRESULT bCap_ExtensionPutTag(int fd, uint32_t hExtension, VARIANT newVal)
Send the b-CAP ID_EXTENSION_PUTTAG packet.
Definition: bcap_client.c:891
#define ID_VARIABLE_PUTID
Definition: bcap_funcid.h:150
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
HRESULT bCap_FileGetSize(int fd, uint32_t hFile, int32_t *pVal)
Send the b-CAP ID_FILE_GETSIZE packet.
Definition: bcap_client.c:1037
#define ID_ROBOT_GOHOME
Definition: bcap_funcid.h:108
#define ID_CONTROLLER_GETVARIABLE
Definition: bcap_funcid.h:45
#define ID_ROBOT_RELEASE
Definition: bcap_funcid.h:123
HRESULT bCap_TaskGetFileName(int fd, uint32_t hTask, BSTR *pVal)
Send the b-CAP ID_TASK_GETFILENAME packet.
Definition: bcap_client.c:1368
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
HRESULT bCap_RobotGetTag(int fd, uint32_t hRobot, VARIANT *pVal)
Send the b-CAP ID_ROBOT_GETTAG packet.
Definition: bcap_client.c:1273
#define ID_COMMAND_EXECUTE
Definition: bcap_funcid.h:154
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_core
Author(s): DENSO WAVE INCORPORATED
autogenerated on Mon Jun 10 2019 13:12:20