bcap_service.cpp
Go to the documentation of this file.
1 
25 #include <stdlib.h>
26 #include <sstream>
28 #include "bcap_core/bcap_funcid.h"
29 #include "bcap_core/bCAPClient/bcap_client.h"
30 #include "bcap_core/RACString/rac_string.h"
31 
32 int main(int argc, char** argv)
33 {
34  ros::init(argc, argv, "bcap_service");
35 
36  HRESULT hr;
37  ros::NodeHandle node;
38 
40 
41  bcapsrv.parseParams();
42 
43  hr = bcapsrv.Connect();
44  if(FAILED(hr)) {
45  ROS_ERROR("Failed to connect. (%X)", hr);
46  return 1;
47  } else {
48  bcapsrv.StartService(node);
49 
50  ros::spin();
51 
52  bcapsrv.StopService();
53  bcapsrv.Disconnect();
54  return 0;
55  }
56 }
57 
58 namespace bcap_service {
59 
61  : m_type(""), m_addr(""),
62  m_port(0), m_timeout(0), m_retry(0), m_wait(0),
63  m_fd(0), m_wdt(0), m_invoke(0)
64 {
65 
66 }
67 
69 {
70  StopService();
71  Disconnect();
72 }
73 
75 {
76  ros::NodeHandle node;
77 
78  if(!node.getParam("conn_type", m_type))
79  {
80  m_type = "tcp";
81  }
82 
83  if(!node.getParam("ip_address", m_addr))
84  {
85  m_addr = "192.168.0.1";
86  }
87 
88  if(!node.getParam("port_number", m_port))
89  {
90  m_port = 5007;
91  }
92 
93  if(!node.getParam("timeout", m_timeout))
94  {
95  m_timeout = 3000;
96  }
97 
98  if(!node.getParam("retry_count", m_retry))
99  {
100  m_retry = 5;
101  }
102 
103  if(!node.getParam("wait_time", m_wait))
104  {
105  m_wait = 0;
106  }
107 
108  if(!node.getParam("watchdog_timer", m_wdt))
109  {
110  m_wdt = 400;
111  }
112 
113  if(!node.getParam("invoke_timeout", m_invoke))
114  {
115  m_invoke = 180000;
116  }
117 }
118 
120 {
121  HRESULT hr;
122  std::stringstream ss1;
123  std::wstringstream ss2;
124 
126 
127  ss1 << m_type << ":" << m_addr << ":" << m_port;
128  hr = bCap_Open_Client(ss1.str().c_str(), m_timeout, m_retry, &m_fd);
129  if(SUCCEEDED(hr)) {
130  ss2 << L",WDT=" << m_wdt << L",InvokeTimeout=" << m_invoke;
131  BSTR bstrOption = SysAllocString(ss2.str().c_str());
132  hr = bCap_ServiceStart(m_fd, bstrOption);
133  SysFreeString(bstrOption);
134  }
135 
136  return hr;
137 }
138 
140 {
141  if(m_fd > 0) {
142  KeyHandle_Vec::iterator it;
143  for(it = m_vecKH.begin(); it != m_vecKH.end(); it++) {
144  switch(it->first){
146  bCap_ControllerDisconnect(m_fd, &it->second);
147  break;
149  bCap_ExtensionRelease(m_fd, &it->second);
150  break;
151  case ID_FILE_RELEASE:
152  bCap_FileRelease(m_fd, &it->second);
153  break;
154  case ID_ROBOT_RELEASE:
155  bCap_RobotRelease(m_fd, &it->second);
156  break;
157  case ID_TASK_RELEASE:
158  bCap_TaskRelease(m_fd, &it->second);
159  break;
160  case ID_VARIABLE_RELEASE:
161  bCap_VariableRelease(m_fd, &it->second);
162  break;
163  case ID_COMMAND_RELEASE:
164  bCap_CommandRelease(m_fd, &it->second);
165  break;
166  case ID_MESSAGE_RELEASE:
167  bCap_MessageRelease(m_fd, &it->second);
168  break;
169  }
170  }
171 
172  m_vecKH.clear();
173 
175 
177  }
178 
179  return S_OK;
180 }
181 
183 {
184  m_svr = node.advertiseService("bcap_service", &BCAPService::CallFunction, this);
185  return S_OK;
186 }
187 
189 {
190  m_svr.shutdown();
191  return S_OK;
192 }
193 
194 const std::string& BCAPService::get_Type() const
195 {
196  return m_type;
197 }
198 
199 void BCAPService::put_Type(const std::string& type)
200 {
201  if(m_fd == 0) {
202  m_type = type;
203  }
204 }
205 
207 {
208  uint32_t value = 0;
209  if(FAILED(bCap_GetTimeout(m_fd, &value))) {
210  value = m_timeout;
211  }
212  return value;
213 }
214 
216 {
217  if(SUCCEEDED(bCap_SetTimeout(m_fd, value))) {
218  m_timeout = value;
219  }
220 }
221 
222 unsigned int BCAPService::get_Retry() const
223 {
224  unsigned int value = 0;
225  if(FAILED(bCap_GetRetry(m_fd, &value))) {
226  value = m_retry;
227  }
228  return value;
229 }
230 
231 void BCAPService::put_Retry(unsigned int value)
232 {
233  if(SUCCEEDED(bCap_SetRetry(m_fd, value))) {
234  m_retry = value;
235  }
236 }
237 
238 bool BCAPService::CallFunction(bcap::Request &req, bcap::Response &res)
239 {
240  HRESULT hr = S_OK;
241  char *chRet = NULL;
242  VARIANT_Vec vntArgs;
243  VARIANT_Ptr vntRet(new VARIANT());
244  VariantInit(vntRet.get());
245 
246  for(int i = 0; i < req.vntArgs.size(); i++) {
247  VARIANT_Ptr vntTmp(new VARIANT());
248  VariantInit(vntTmp.get());
250  req.vntArgs[i].vt, req.vntArgs[i].value.c_str(),
251  vntTmp.get());
252  if(FAILED(hr)) goto err_proc;
253  vntArgs.push_back(*vntTmp.get());
254  }
255 
256  hr = ExecFunction(req.func_id, vntArgs, vntRet);
257  if(FAILED(hr)) goto err_proc;
258 
259  hr = ConvertVariant2RacStr(*vntRet.get(), &chRet);
260  if(FAILED(hr)) goto err_proc;
261 
262  res.HRESULT = S_OK;
263  res.vntRet.vt = vntRet->vt;
264  res.vntRet.value = chRet;
265 
266  free(chRet);
267 
268 post_proc:
269  return true;
270 
271 err_proc:
272  res.HRESULT = hr;
273  res.vntRet.vt = VT_EMPTY;
274  res.vntRet.value = "";
275 
276  goto post_proc;
277 }
278 
280  int32_t func_id, VARIANT_Vec& vntArgs,
281  VARIANT_Ptr& vntRet)
282 {
283  HRESULT hr = E_INVALIDARG;
284  KeyHandle tmpKH(0, 0);
285 
286  try {
287  switch(func_id) {
288  // Controller
290  vntRet->vt = VT_UI4;
292  vntArgs.at(0).bstrVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal, vntArgs.at(3).bstrVal,
293  &vntRet->ulVal);
294  tmpKH.first = ID_CONTROLLER_DISCONNECT;
295  break;
297  tmpKH.second = vntArgs.at(0).ulVal;
299  &vntArgs.at(0).ulVal);
300  break;
302  vntRet->vt = VT_UI4;
304  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
305  &vntRet->ulVal);
306  tmpKH.first = ID_EXTENSION_RELEASE;
307  break;
309  vntRet->vt = VT_UI4;
311  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
312  &vntRet->ulVal);
313  tmpKH.first = ID_FILE_RELEASE;
314  break;
316  vntRet->vt = VT_UI4;
318  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
319  &vntRet->ulVal);
320  tmpKH.first = ID_ROBOT_RELEASE;
321  break;
323  vntRet->vt = VT_UI4;
325  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
326  &vntRet->ulVal);
327  tmpKH.first = ID_TASK_RELEASE;
328  break;
330  vntRet->vt = VT_UI4;
332  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
333  &vntRet->ulVal);
334  tmpKH.first = ID_VARIABLE_RELEASE;
335  break;
337  vntRet->vt = VT_UI4;
339  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
340  &vntRet->ulVal);
341  tmpKH.first = ID_COMMAND_RELEASE;
342  break;
345  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
346  vntRet.get());
347  break;
350  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
351  vntRet.get());
352  break;
355  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
356  vntRet.get());
357  break;
360  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
361  vntRet.get());
362  break;
365  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
366  vntRet.get());
367  break;
370  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
371  vntRet.get());
372  break;
375  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2),
376  vntRet.get());
377  break;
379  vntRet->vt = VT_UI4;
381  vntArgs.at(0).ulVal,
382  &vntRet->ulVal);
383  tmpKH.first = ID_MESSAGE_RELEASE;
384  break;
386  vntRet->vt = VT_I4;
388  vntArgs.at(0).ulVal,
389  &vntRet->lVal);
390  break;
392  vntRet->vt = VT_BSTR;
394  vntArgs.at(0).ulVal,
395  &vntRet->bstrVal);
396  break;
398  vntRet->vt = VT_BSTR;
400  vntArgs.at(0).ulVal,
401  &vntRet->bstrVal);
402  break;
405  vntArgs.at(0).ulVal,
406  vntRet.get());
407  break;
410  vntArgs.at(0).ulVal, vntArgs.at(1));
411  break;
412  case ID_CONTROLLER_GETID:
414  vntArgs.at(0).ulVal,
415  vntRet.get());
416  break;
417  case ID_CONTROLLER_PUTID:
419  vntArgs.at(0).ulVal, vntArgs.at(1));
420  break;
421  // Extension
423  vntRet->vt = VT_UI4;
425  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
426  &vntRet->ulVal);
427  tmpKH.first = ID_VARIABLE_RELEASE;
428  break;
431  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
432  vntRet.get());
433  break;
436  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2),
437  vntRet.get());
438  break;
440  vntRet->vt = VT_I4;
442  vntArgs.at(0).ulVal,
443  &vntRet->lVal);
444  break;
446  vntRet->vt = VT_BSTR;
448  vntArgs.at(0).ulVal,
449  &vntRet->bstrVal);
450  break;
452  vntRet->vt = VT_BSTR;
454  vntArgs.at(0).ulVal,
455  &vntRet->bstrVal);
456  break;
457  case ID_EXTENSION_GETTAG:
459  vntArgs.at(0).ulVal,
460  vntRet.get());
461  break;
462  case ID_EXTENSION_PUTTAG:
464  vntArgs.at(0).ulVal, vntArgs.at(1));
465  break;
466  case ID_EXTENSION_GETID:
468  vntArgs.at(0).ulVal,
469  vntRet.get());
470  break;
471  case ID_EXTENSION_PUTID:
473  vntArgs.at(0).ulVal, vntArgs.at(1));
474  break;
476  tmpKH.second = vntArgs.at(0).ulVal;
478  &vntArgs.at(0).ulVal);
479  break;
480  // File
481  case ID_FILE_GETFILE:
482  vntRet->vt = VT_UI4;
483  hr = bCap_FileGetFile(m_fd,
484  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
485  &vntRet->ulVal);
486  tmpKH.first = ID_FILE_RELEASE;
487  break;
488  case ID_FILE_GETVARIABLE:
489  vntRet->vt = VT_UI4;
491  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
492  &vntRet->ulVal);
493  tmpKH.first = ID_VARIABLE_RELEASE;
494  break;
497  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
498  vntRet.get());
499  break;
502  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
503  vntRet.get());
504  break;
505  case ID_FILE_EXECUTE:
506  hr = bCap_FileExecute(m_fd,
507  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2),
508  vntRet.get());
509  break;
510  case ID_FILE_COPY:
511  hr = bCap_FileCopy(m_fd,
512  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal);
513  break;
514  case ID_FILE_DELETE:
515  hr = bCap_FileDelete(m_fd,
516  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal);
517  break;
518  case ID_FILE_MOVE:
519  hr = bCap_FileMove(m_fd,
520  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal);
521  break;
522  case ID_FILE_RUN:
523  vntRet->vt = VT_BSTR;
524  hr = bCap_FileRun(m_fd,
525  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
526  &vntRet->bstrVal);
527  break;
530  vntArgs.at(0).ulVal,
531  vntRet.get());
532  break;
535  vntArgs.at(0).ulVal,
536  vntRet.get());
537  break;
540  vntArgs.at(0).ulVal,
541  vntRet.get());
542  break;
543  case ID_FILE_GETPATH:
544  vntRet->vt = VT_BSTR;
545  hr = bCap_FileGetPath(m_fd,
546  vntArgs.at(0).ulVal,
547  &vntRet->bstrVal);
548  break;
549  case ID_FILE_GETSIZE:
550  vntRet->vt = VT_I4;
551  hr = bCap_FileGetSize(m_fd,
552  vntArgs.at(0).ulVal,
553  &vntRet->lVal);
554  break;
555  case ID_FILE_GETTYPE:
556  vntRet->vt = VT_BSTR;
557  hr = bCap_FileGetType(m_fd,
558  vntArgs.at(0).ulVal,
559  &vntRet->bstrVal);
560  break;
561  case ID_FILE_GETVALUE:
562  hr = bCap_FileGetValue(m_fd,
563  vntArgs.at(0).ulVal,
564  vntRet.get());
565  break;
566  case ID_FILE_PUTVALUE:
567  hr = bCap_FilePutValue(m_fd,
568  vntArgs.at(0).ulVal, vntArgs.at(1));
569  break;
571  vntRet->vt = VT_I4;
573  vntArgs.at(0).ulVal,
574  &vntRet->lVal);
575  break;
576  case ID_FILE_GETHELP:
577  vntRet->vt = VT_BSTR;
578  hr = bCap_FileGetHelp(m_fd,
579  vntArgs.at(0).ulVal,
580  &vntRet->bstrVal);
581  break;
582  case ID_FILE_GETNAME:
583  vntRet->vt = VT_BSTR;
584  hr = bCap_FileGetName(m_fd,
585  vntArgs.at(0).ulVal,
586  &vntRet->bstrVal);
587  break;
588  case ID_FILE_GETTAG:
589  hr = bCap_FileGetTag(m_fd,
590  vntArgs.at(0).ulVal,
591  vntRet.get());
592  break;
593  case ID_FILE_PUTTAG:
594  hr = bCap_FilePutTag(m_fd,
595  vntArgs.at(0).ulVal, vntArgs.at(1));
596  break;
597  case ID_FILE_GETID:
598  hr = bCap_FileGetID(m_fd,
599  vntArgs.at(0).ulVal,
600  vntRet.get());
601  break;
602  case ID_FILE_PUTID:
603  hr = bCap_FilePutID(m_fd,
604  vntArgs.at(0).ulVal, vntArgs.at(1));
605  break;
606  case ID_FILE_RELEASE:
607  tmpKH.second = vntArgs.at(0).ulVal;
608  hr = bCap_FileRelease(m_fd,
609  &vntArgs.at(0).ulVal);
610  break;
611  // Robot
613  vntRet->vt = VT_UI4;
615  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
616  &vntRet->ulVal);
617  tmpKH.first = ID_VARIABLE_RELEASE;
618  break;
621  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
622  vntRet.get());
623  break;
624  case ID_ROBOT_EXECUTE:
625  hr = bCap_RobotExecute(m_fd,
626  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2),
627  vntRet.get());
628  break;
629  case ID_ROBOT_ACCELERATE:
631  vntArgs.at(0).ulVal, vntArgs.at(1).lVal, vntArgs.at(2).fltVal, vntArgs.at(3).fltVal);
632  break;
633  case ID_ROBOT_CHANGE:
634  hr = bCap_RobotChange(m_fd,
635  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal);
636  break;
637  case ID_ROBOT_CHUCK:
638  hr = bCap_RobotChuck(m_fd,
639  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal);
640  break;
641  case ID_ROBOT_DRIVE:
642  hr = bCap_RobotDrive(m_fd,
643  vntArgs.at(0).ulVal, vntArgs.at(1).lVal, vntArgs.at(2).fltVal, vntArgs.at(3).bstrVal);
644  break;
645  case ID_ROBOT_GOHOME:
646  hr = bCap_RobotGoHome(m_fd,
647  vntArgs.at(0).ulVal);
648  break;
649  case ID_ROBOT_HALT:
650  hr = bCap_RobotHalt(m_fd,
651  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal);
652  break;
653  case ID_ROBOT_HOLD:
654  hr = bCap_RobotHold(m_fd,
655  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal);
656  break;
657  case ID_ROBOT_MOVE:
658  hr = bCap_RobotMove(m_fd,
659  vntArgs.at(0).ulVal, vntArgs.at(1).lVal, vntArgs.at(2), vntArgs.at(3).bstrVal);
660  break;
661  case ID_ROBOT_ROTATE:
662  hr = bCap_RobotRotate(m_fd,
663  vntArgs.at(0).ulVal, vntArgs.at(1), vntArgs.at(2).fltVal, vntArgs.at(3), vntArgs.at(4).bstrVal);
664  break;
665  case ID_ROBOT_SPEED:
666  hr = bCap_RobotSpeed(m_fd,
667  vntArgs.at(0).ulVal, vntArgs.at(1).lVal, vntArgs.at(2).fltVal);
668  break;
669  case ID_ROBOT_UNCHUCK:
670  hr = bCap_RobotUnchuck(m_fd,
671  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal);
672  break;
673  case ID_ROBOT_UNHOLD:
674  hr = bCap_RobotUnhold(m_fd,
675  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal);
676  break;
678  vntRet->vt = VT_I4;
680  vntArgs.at(0).ulVal,
681  &vntRet->lVal);
682  break;
683  case ID_ROBOT_GETHELP:
684  vntRet->vt = VT_BSTR;
685  hr = bCap_RobotGetHelp(m_fd,
686  vntArgs.at(0).ulVal,
687  &vntRet->bstrVal);
688  break;
689  case ID_ROBOT_GETNAME:
690  vntRet->vt = VT_BSTR;
691  hr = bCap_RobotGetName(m_fd,
692  vntArgs.at(0).ulVal,
693  &vntRet->bstrVal);
694  break;
695  case ID_ROBOT_GETTAG:
696  hr = bCap_RobotGetTag(m_fd,
697  vntArgs.at(0).ulVal,
698  vntRet.get());
699  break;
700  case ID_ROBOT_PUTTAG:
701  hr = bCap_RobotPutTag(m_fd,
702  vntArgs.at(0).ulVal, vntArgs.at(1));
703  break;
704  case ID_ROBOT_GETID:
705  hr = bCap_RobotGetID(m_fd,
706  vntArgs.at(0).ulVal,
707  vntRet.get());
708  break;
709  case ID_ROBOT_PUTID:
710  hr = bCap_RobotPutID(m_fd,
711  vntArgs.at(0).ulVal, vntArgs.at(1));
712  break;
713  case ID_ROBOT_RELEASE:
714  tmpKH.second = vntArgs.at(0).ulVal;
715  hr = bCap_RobotRelease(m_fd,
716  &vntArgs.at(0).ulVal);
717  break;
718  // Task
719  case ID_TASK_GETVARIABLE:
720  vntRet->vt = VT_UI4;
722  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2).bstrVal,
723  &vntRet->ulVal);
724  tmpKH.first = ID_VARIABLE_RELEASE;
725  break;
728  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal,
729  vntRet.get());
730  break;
731  case ID_TASK_EXECUTE:
732  hr = bCap_TaskExecute(m_fd,
733  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal, vntArgs.at(2),
734  vntRet.get());
735  break;
736  case ID_TASK_START:
737  hr = bCap_TaskStart(m_fd,
738  vntArgs.at(0).ulVal, vntArgs.at(1).lVal, vntArgs.at(2).bstrVal);
739  break;
740  case ID_TASK_STOP:
741  hr = bCap_TaskStop(m_fd,
742  vntArgs.at(0).ulVal, vntArgs.at(1).lVal, vntArgs.at(2).bstrVal);
743  break;
744  case ID_TASK_DELETE:
745  hr = bCap_TaskDelete(m_fd,
746  vntArgs.at(0).ulVal, vntArgs.at(1).bstrVal);
747  break;
748  case ID_TASK_GETFILENAME:
749  vntRet->vt = VT_BSTR;
751  vntArgs.at(0).ulVal,
752  &vntRet->bstrVal);
753  break;
755  vntRet->vt = VT_I4;
757  vntArgs.at(0).ulVal,
758  &vntRet->lVal);
759  break;
760  case ID_TASK_GETHELP:
761  vntRet->vt = VT_BSTR;
762  hr = bCap_TaskGetHelp(m_fd,
763  vntArgs.at(0).ulVal,
764  &vntRet->bstrVal);
765  break;
766  case ID_TASK_GETNAME:
767  vntRet->vt = VT_BSTR;
768  hr = bCap_TaskGetName(m_fd,
769  vntArgs.at(0).ulVal,
770  &vntRet->bstrVal);
771  break;
772  case ID_TASK_GETTAG:
773  hr = bCap_TaskGetTag(m_fd,
774  vntArgs.at(0).ulVal,
775  vntRet.get());
776  break;
777  case ID_TASK_PUTTAG:
778  hr = bCap_TaskPutTag(m_fd,
779  vntArgs.at(0).ulVal, vntArgs.at(1));
780  break;
781  case ID_TASK_GETID:
782  hr = bCap_TaskGetID(m_fd,
783  vntArgs.at(0).ulVal,
784  vntRet.get());
785  break;
786  case ID_TASK_PUTID:
787  hr = bCap_TaskPutID(m_fd,
788  vntArgs.at(0).ulVal, vntArgs.at(1));
789  break;
790  case ID_TASK_RELEASE:
791  tmpKH.second = vntArgs.at(0).ulVal;
792  hr = bCap_TaskRelease(m_fd,
793  &vntArgs.at(0).ulVal);
794  break;
795  // Variable
798  vntArgs.at(0).ulVal,
799  vntRet.get());
800  break;
803  vntArgs.at(0).ulVal,
804  vntRet.get());
805  break;
808  vntArgs.at(0).ulVal, vntArgs.at(1));
809  break;
811  vntRet->vt = VT_I4;
813  vntArgs.at(0).ulVal,
814  &vntRet->lVal);
815  break;
816  case ID_VARIABLE_GETHELP:
817  vntRet->vt = VT_BSTR;
819  vntArgs.at(0).ulVal,
820  &vntRet->bstrVal);
821  break;
822  case ID_VARIABLE_GETNAME:
823  vntRet->vt = VT_BSTR;
825  vntArgs.at(0).ulVal,
826  &vntRet->bstrVal);
827  break;
828  case ID_VARIABLE_GETTAG:
830  vntArgs.at(0).ulVal,
831  vntRet.get());
832  break;
833  case ID_VARIABLE_PUTTAG:
835  vntArgs.at(0).ulVal, vntArgs.at(1));
836  break;
837  case ID_VARIABLE_GETID:
839  vntArgs.at(0).ulVal,
840  vntRet.get());
841  break;
842  case ID_VARIABLE_PUTID:
844  vntArgs.at(0).ulVal, vntArgs.at(1));
845  break;
847  vntRet->vt = VT_I4;
849  vntArgs.at(0).ulVal,
850  &vntRet->lVal);
851  break;
852  case ID_VARIABLE_RELEASE:
853  tmpKH.second = vntArgs.at(0).ulVal;
855  &vntArgs.at(0).ulVal);
856  break;
857  // Command
858  case ID_COMMAND_EXECUTE:
860  vntArgs.at(0).ulVal, vntArgs.at(1).lVal,
861  vntRet.get());
862  break;
863  case ID_COMMAND_CANCEL:
865  vntArgs.at(0).ulVal);
866  break;
868  vntRet->vt = VT_I4;
870  vntArgs.at(0).ulVal,
871  &vntRet->lVal);
872  break;
875  vntArgs.at(0).ulVal, vntArgs.at(1).lVal);
876  break;
877  case ID_COMMAND_GETSTATE:
878  vntRet->vt = VT_I4;
880  vntArgs.at(0).ulVal,
881  &vntRet->lVal);
882  break;
885  vntArgs.at(0).ulVal,
886  vntRet.get());
887  break;
890  vntArgs.at(0).ulVal, vntArgs.at(1));
891  break;
894  vntArgs.at(0).ulVal,
895  vntRet.get());
896  break;
898  vntRet->vt = VT_I4;
900  vntArgs.at(0).ulVal,
901  &vntRet->lVal);
902  break;
903  case ID_COMMAND_GETHELP:
904  vntRet->vt = VT_BSTR;
906  vntArgs.at(0).ulVal,
907  &vntRet->bstrVal);
908  break;
909  case ID_COMMAND_GETNAME:
910  vntRet->vt = VT_BSTR;
912  vntArgs.at(0).ulVal,
913  &vntRet->bstrVal);
914  break;
915  case ID_COMMAND_GETTAG:
917  vntArgs.at(0).ulVal,
918  vntRet.get());
919  break;
920  case ID_COMMAND_PUTTAG:
922  vntArgs.at(0).ulVal, vntArgs.at(1));
923  break;
924  case ID_COMMAND_GETID:
925  hr = bCap_CommandGetID(m_fd,
926  vntArgs.at(0).ulVal,
927  vntRet.get());
928  break;
929  case ID_COMMAND_PUTID:
930  hr = bCap_CommandPutID(m_fd,
931  vntArgs.at(0).ulVal, vntArgs.at(1));
932  break;
933  case ID_COMMAND_RELEASE:
934  tmpKH.second = vntArgs.at(0).ulVal;
936  &vntArgs.at(0).ulVal);
937  break;
938  case ID_MESSAGE_REPLY:
939  hr = bCap_MessageReply(m_fd,
940  vntArgs.at(0).ulVal, vntArgs.at(1));
941  break;
942  case ID_MESSAGE_CLEAR:
943  hr = bCap_MessageClear(m_fd,
944  vntArgs.at(0).ulVal);
945  break;
948  vntArgs.at(0).ulVal,
949  vntRet.get());
950  break;
952  vntRet->vt = VT_BSTR;
954  vntArgs.at(0).ulVal,
955  &vntRet->bstrVal);
956  break;
958  vntRet->vt = VT_BSTR;
960  vntArgs.at(0).ulVal,
961  &vntRet->bstrVal);
962  break;
964  vntRet->vt = VT_I4;
966  vntArgs.at(0).ulVal,
967  &vntRet->lVal);
968  break;
970  vntRet->vt = VT_I4;
972  vntArgs.at(0).ulVal,
973  &vntRet->lVal);
974  break;
976  vntRet->vt = VT_BSTR;
978  vntArgs.at(0).ulVal,
979  &vntRet->bstrVal);
980  break;
981  case ID_MESSAGE_GETVALUE:
983  vntArgs.at(0).ulVal,
984  vntRet.get());
985  break;
986  case ID_MESSAGE_RELEASE:
987  tmpKH.second = vntArgs.at(0).ulVal;
989  &vntArgs.at(0).ulVal);
990  break;
991  }
992  } catch(std::out_of_range&) {
993  hr = DISP_E_BADINDEX;
994  }
995 
996  if(hr == S_OK) {
997  if(tmpKH.first > 0) {
998  tmpKH.second = vntRet->ulVal;
999  m_vecKH.push_back(tmpKH);
1000  }
1001  else if(tmpKH.second > 0) {
1002  KeyHandle_Vec::iterator it;
1003  for(it = m_vecKH.begin(); it != m_vecKH.end(); it++) {
1004  if((func_id == it->first)
1005  && (tmpKH.second == it->second))
1006  {
1007  m_vecKH.erase(it);
1008  break;
1009  }
1010  }
1011  }
1012  }
1013 
1014  return hr;
1015 }
1016 
1017 }
1018 
HRESULT bCap_CommandPutID(int fd, uint32_t hCommand, VARIANT newVal)
#define ID_MESSAGE_GETSOURCE
HRESULT bCap_TaskGetVariable(int fd, uint32_t hTask, BSTR bstrName, BSTR bstrOption, uint32_t *hVariable)
HRESULT bCap_ControllerGetExtension(int fd, uint32_t hController, BSTR bstrName, BSTR bstrOption, uint32_t *hExtension)
#define ID_FILE_GETHELP
HRESULT bCap_RobotHalt(int fd, uint32_t hRobot, BSTR bstrOption)
void SysFreeString(BSTR bstr)
HRESULT bCap_CommandGetParameters(int fd, uint32_t hCommand, VARIANT *pVal)
#define ID_COMMAND_GETATTRIBUTE
HRESULT bCap_TaskGetID(int fd, uint32_t hTask, VARIANT *pVal)
#define ID_TASK_GETVARIABLE
HRESULT bCap_FilePutValue(int fd, uint32_t hFile, VARIANT newVal)
HRESULT bCap_ControllerGetAttribute(int fd, uint32_t hController, int32_t *pVal)
HRESULT bCap_VariableGetAttribute(int fd, uint32_t hVariable, int32_t *pVal)
#define ID_VARIABLE_GETVALUE
#define ID_FILE_RELEASE
#define ID_CONTROLLER_GETROBOTNAMES
bool CallFunction(bcap::Request &req, bcap::Response &res)
unsigned uint32_t
HRESULT bCap_RobotGetID(int fd, uint32_t hRobot, VARIANT *pVal)
HRESULT bCap_MessageClear(int fd, uint32_t hMessage)
#define ID_CONTROLLER_EXECUTE
HRESULT bCap_FilePutTag(int fd, uint32_t hFile, VARIANT newVal)
HRESULT bCap_ExtensionGetTag(int fd, uint32_t hExtension, VARIANT *pVal)
HRESULT bCap_CommandGetID(int fd, uint32_t hCommand, VARIANT *pVal)
#define ID_FILE_GETTAG
#define ID_FILE_RUN
HRESULT ConvertRacStr2Variant(uint16_t vt, const char *chSrc, VARIANT *pvargDest)
HRESULT bCap_MessageGetSource(int fd, uint32_t hMessage, BSTR *pVal)
#define ID_ROBOT_DRIVE
HRESULT bCap_RobotPutTag(int fd, uint32_t hRobot, VARIANT newVal)
#define ID_FILE_GETTYPE
HRESULT bCap_ControllerGetVariableNames(int fd, uint32_t hController, BSTR bstrOption, VARIANT *pVal)
HRESULT bCap_SetTimeout(int fd, uint32_t timeout)
HRESULT bCap_RobotGoHome(int fd, uint32_t hRobot)
HRESULT bCap_ControllerGetVariable(int fd, uint32_t hController, BSTR bstrName, BSTR bstrOption, uint32_t *hVariable)
#define ID_CONTROLLER_PUTTAG
#define ID_EXTENSION_PUTID
#define ID_FILE_GETDATELASTMODIFIED
HRESULT bCap_VariableRelease(int fd, uint32_t *hVariable)
HRESULT bCap_ControllerGetTask(int fd, uint32_t hController, BSTR bstrName, BSTR bstrOption, uint32_t *hTask)
unsigned int get_Retry() const
HRESULT bCap_VariablePutValue(int fd, uint32_t hVariable, VARIANT newVal)
#define ID_TASK_GETVARIABLENAMES
HRESULT bCap_VariableGetMicrosecond(int fd, uint32_t hVariable, int32_t *pVal)
#define ID_CONTROLLER_CONNECT
HRESULT bCap_FileGetDateLastModified(int fd, uint32_t hFile, VARIANT *pVal)
#define ID_EXTENSION_GETID
HRESULT bCap_ExtensionPutID(int fd, uint32_t hExtension, VARIANT newVal)
#define ID_TASK_DELETE
HRESULT bCap_CommandExecute(int fd, uint32_t hCommand, int32_t lMode, VARIANT *pVal)
HRESULT bCap_ControllerGetCommandNames(int fd, uint32_t hController, BSTR bstrOption, VARIANT *pVal)
#define S_OK
#define ID_COMMAND_PUTID
HRESULT bCap_ExtensionGetHelp(int fd, uint32_t hExtension, BSTR *pVal)
bool sleep() const
HRESULT bCap_FileGetFile(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption, uint32_t *hFile2)
HRESULT bCap_FileGetHelp(int fd, uint32_t hFile, BSTR *pVal)
#define ID_EXTENSION_GETATTRIBUTE
HRESULT StartService(ros::NodeHandle &node)
#define ID_FILE_GETFILENAMES
#define ID_ROBOT_GETTAG
HRESULT bCap_TaskStop(int fd, uint32_t hTask, int32_t lMode, BSTR bstrOption)
HRESULT bCap_MessageReply(int fd, uint32_t hMessage, VARIANT vntData)
HRESULT ExecFunction(int32_t func_id, VARIANT_Vec &vntArgs, VARIANT_Ptr &vntRet)
HRESULT bCap_TaskGetTag(int fd, uint32_t hTask, VARIANT *pVal)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
wchar_t * BSTR
HRESULT bCap_FileGetVariable(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption, uint32_t *hVariable)
HRESULT bCap_ServiceStop(int fd)
#define ID_FILE_PUTID
HRESULT bCap_FileGetType(int fd, uint32_t hFile, BSTR *pVal)
#define ID_MESSAGE_GETDATETIME
std::vector< VARIANT, VariantAllocator< VARIANT > > VARIANT_Vec
Definition: bcap_service.h:47
HRESULT bCap_RobotGetAttribute(int fd, uint32_t hRobot, int32_t *pVal)
#define ID_TASK_STOP
HRESULT bCap_CommandGetTimeout(int fd, uint32_t hCommand, int32_t *pVal)
HRESULT bCap_CommandGetName(int fd, uint32_t hCommand, BSTR *pVal)
#define ID_MESSAGE_GETVALUE
#define ID_ROBOT_ROTATE
HRESULT bCap_FileGetTag(int fd, uint32_t hFile, VARIANT *pVal)
#define ID_VARIABLE_GETHELP
#define ID_ROBOT_EXECUTE
HRESULT bCap_TaskGetName(int fd, uint32_t hTask, BSTR *pVal)
#define ID_ROBOT_UNCHUCK
#define ID_EXTENSION_PUTTAG
int main(int argc, char **argv)
HRESULT bCap_RobotPutID(int fd, uint32_t hRobot, VARIANT newVal)
HRESULT bCap_RobotGetName(int fd, uint32_t hRobot, BSTR *pVal)
#define DISP_E_BADINDEX
#define ID_VARIABLE_RELEASE
void put_Type(const std::string &type)
#define ID_ROBOT_GETATTRIBUTE
HRESULT bCap_RobotRelease(int fd, uint32_t *hRobot)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
#define ID_TASK_RELEASE
#define ID_ROBOT_UNHOLD
HRESULT bCap_FileGetDateCreated(int fd, uint32_t hFile, VARIANT *pVal)
HRESULT bCap_Open_Client(const char *connect, uint32_t timeout, unsigned int retry, int *pfd)
#define ID_FILE_GETVARIABLENAMES
#define ID_FILE_EXECUTE
#define FAILED(hr)
#define ID_VARIABLE_GETNAME
#define ID_CONTROLLER_GETMESSAGE
#define ID_TASK_GETID
#define ID_TASK_GETFILENAME
HRESULT bCap_SetRetry(int fd, unsigned int retry)
#define ID_MESSAGE_CLEAR
HRESULT bCap_ControllerGetID(int fd, uint32_t hController, VARIANT *pVal)
HRESULT bCap_MessageGetValue(int fd, uint32_t hMessage, VARIANT *pVal)
HRESULT bCap_CommandGetHelp(int fd, uint32_t hCommand, BSTR *pVal)
HRESULT bCap_TaskPutTag(int fd, uint32_t hTask, VARIANT newVal)
HRESULT bCap_TaskGetHelp(int fd, uint32_t hTask, BSTR *pVal)
VT_I4
HRESULT bCap_RobotUnchuck(int fd, uint32_t hRobot, BSTR bstrOption)
#define ID_CONTROLLER_DISCONNECT
#define ID_COMMAND_GETSTATE
HRESULT bCap_RobotMove(int fd, uint32_t hRobot, int32_t lComp, VARIANT vntPose, BSTR bstrOption)
#define ID_TASK_PUTTAG
#define ID_MESSAGE_RELEASE
#define E_INVALIDARG
VT_BSTR
#define ID_ROBOT_HOLD
#define ID_COMMAND_GETPARAMETERS
HRESULT bCap_TaskExecute(int fd, uint32_t hTask, BSTR bstrCommand, VARIANT vntParam, VARIANT *pVal)
HRESULT bCap_CommandCancel(int fd, uint32_t hCommand)
HRESULT bCap_ControllerGetMessage(int fd, uint32_t hController, uint32_t *hMessage)
#define ID_EXTENSION_GETVARIABLE
HRESULT bCap_VariableGetTag(int fd, uint32_t hVariable, VARIANT *pVal)
#define ID_TASK_PUTID
HRESULT bCap_FileGetID(int fd, uint32_t hFile, VARIANT *pVal)
HRESULT bCap_FileGetAttribute(int fd, uint32_t hFile, int32_t *pVal)
VT_EMPTY
HRESULT bCap_TaskPutID(int fd, uint32_t hTask, VARIANT newVal)
#define ID_FILE_GETVALUE
#define ID_FILE_PUTTAG
void put_Timeout(uint32_t value)
HRESULT bCap_ExtensionGetVariableNames(int fd, uint32_t hExtension, BSTR bstrOption, VARIANT *pVal)
HRESULT bCap_VariablePutID(int fd, uint32_t hVariable, VARIANT newVal)
#define ID_EXTENSION_RELEASE
void VariantInit(VARIANT *pvarg)
#define ID_ROBOT_ACCELERATE
HRESULT bCap_ControllerGetExtensionNames(int fd, uint32_t hController, BSTR bstrOption, VARIANT *pVal)
#define ID_VARIABLE_GETMICROSECOND
HRESULT bCap_FileGetName(int fd, uint32_t hFile, BSTR *pVal)
#define ID_FILE_GETNAME
#define ID_TASK_GETTAG
#define ID_FILE_GETID
HRESULT bCap_RobotChuck(int fd, uint32_t hRobot, BSTR bstrOption)
HRESULT bCap_ServiceStart(int fd, BSTR bstrOption)
HRESULT bCap_RobotUnhold(int fd, uint32_t hRobot, BSTR bstrOption)
HRESULT bCap_RobotGetHelp(int fd, uint32_t hRobot, BSTR *pVal)
HRESULT bCap_ControllerGetCommand(int fd, uint32_t hController, BSTR bstrName, BSTR bstrOption, uint32_t *hCommand)
HRESULT bCap_ControllerGetHelp(int fd, uint32_t hController, BSTR *pVal)
#define ID_CONTROLLER_GETFILENAMES
int32_t HRESULT
HRESULT bCap_ControllerGetTaskNames(int fd, uint32_t hController, BSTR bstrOption, VARIANT *pVal)
#define ID_COMMAND_GETRESULT
HRESULT bCap_ExtensionRelease(int fd, uint32_t *hExtension)
#define ID_VARIABLE_GETATTRIBUTE
HRESULT bCap_TaskRelease(int fd, uint32_t *hTask)
HRESULT bCap_RobotExecute(int fd, uint32_t hRobot, BSTR bstrCommand, VARIANT vntParam, VARIANT *pVal)
#define ID_CONTROLLER_GETCOMMAND
#define ID_FILE_GETFILE
#define ID_TASK_START
HRESULT bCap_VariableGetName(int fd, uint32_t hVariable, BSTR *pVal)
#define ID_VARIABLE_GETDATETIME
BSTR SysAllocString(const wchar_t *sz)
#define ID_MESSAGE_GETSERIALNUMBER
#define ID_COMMAND_GETTIMEOUT
HRESULT bCap_MessageRelease(int fd, uint32_t *hMessage)
HRESULT bCap_CommandPutParameters(int fd, uint32_t hCommand, VARIANT newVal)
#define ID_MESSAGE_REPLY
VT_UI4
HRESULT bCap_FileGetVariableNames(int fd, uint32_t hFile, BSTR bstrOption, VARIANT *pVal)
#define ID_CONTROLLER_PUTID
HRESULT bCap_ControllerExecute(int fd, uint32_t hController, BSTR bstrCommand, VARIANT vntParam, VARIANT *pVal)
HRESULT ConvertVariant2RacStr(VARIANT varSrc, char **chDest)
#define ID_CONTROLLER_GETTAG
HRESULT bCap_VariablePutTag(int fd, uint32_t hVariable, VARIANT newVal)
#define ID_TASK_GETATTRIBUTE
boost::interprocess::unique_ptr< VARIANT, variant_deleter > VARIANT_Ptr
Definition: bcap_service.h:46
HRESULT bCap_ControllerPutID(int fd, uint32_t hController, VARIANT newVal)
#define ID_ROBOT_GETHELP
HRESULT bCap_FileMove(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption)
HRESULT bCap_ControllerConnect(int fd, BSTR bstrName, BSTR bstrProvider, BSTR bstrMachine, BSTR bstrOption, uint32_t *hController)
HRESULT bCap_FilePutID(int fd, uint32_t hFile, VARIANT newVal)
#define ID_ROBOT_GETVARIABLENAMES
#define ID_MESSAGE_GETDESCRIPTION
HRESULT bCap_CommandGetState(int fd, uint32_t hCommand, int32_t *pVal)
#define ID_ROBOT_PUTID
HRESULT bCap_VariableGetID(int fd, uint32_t hVariable, VARIANT *pVal)
#define SUCCEEDED(hr)
HRESULT bCap_FileDelete(int fd, uint32_t hFile, BSTR bstrOption)
#define ID_COMMAND_GETNAME
ROSCPP_DECL void spin()
HRESULT bCap_ControllerGetName(int fd, uint32_t hController, BSTR *pVal)
HRESULT bCap_ControllerGetFileNames(int fd, uint32_t hController, BSTR bstrOption, VARIANT *pVal)
HRESULT bCap_ControllerGetTag(int fd, uint32_t hController, VARIANT *pVal)
ros::ServiceServer m_svr
Definition: bcap_service.h:97
#define ID_EXTENSION_GETNAME
HRESULT bCap_VariableGetHelp(int fd, uint32_t hVariable, BSTR *pVal)
#define ID_VARIABLE_PUTTAG
#define ID_ROBOT_GETVARIABLE
HRESULT bCap_CommandGetTag(int fd, uint32_t hCommand, VARIANT *pVal)
HRESULT bCap_RobotDrive(int fd, uint32_t hRobot, int32_t lNo, float fMov, BSTR bstrOption)
#define ID_ROBOT_GETNAME
HRESULT bCap_CommandGetAttribute(int fd, uint32_t hCommand, int32_t *pVal)
HRESULT bCap_RobotAccelerate(int fd, uint32_t hRobot, int32_t lAxis, float fAccel, float fDecel)
HRESULT bCap_ExtensionGetAttribute(int fd, uint32_t hExtension, int32_t *pVal)
#define ID_CONTROLLER_GETTASKNAMES
HRESULT bCap_RobotGetVariable(int fd, uint32_t hRobot, BSTR bstrName, BSTR bstrOption, uint32_t *hVariable)
#define ID_VARIABLE_PUTVALUE
#define ID_ROBOT_CHANGE
#define ID_FILE_MOVE
#define ID_FILE_GETDATELASTACCESSED
#define ID_COMMAND_RELEASE
#define ID_FILE_GETSIZE
#define ID_ROBOT_SPEED
HRESULT bCap_CommandGetResult(int fd, uint32_t hCommand, VARIANT *pVal)
HRESULT bCap_RobotHold(int fd, uint32_t hRobot, BSTR bstrOption)
#define ID_FILE_GETDATECREATED
#define ID_FILE_GETPATH
HRESULT bCap_ControllerGetFile(int fd, uint32_t hController, BSTR bstrName, BSTR bstrOption, uint32_t *hFile)
HRESULT bCap_FileCopy(int fd, uint32_t hFile, BSTR bstrName, BSTR bstrOption)
#define ID_FILE_PUTVALUE
#define ID_ROBOT_PUTTAG
HRESULT bCap_ExtensionExecute(int fd, uint32_t hExtension, BSTR bstrCommand, VARIANT vntParam, VARIANT *pVal)
std::pair< int32_t, uint32_t > KeyHandle
Definition: bcap_service.h:36
#define ID_CONTROLLER_GETNAME
#define ID_EXTENSION_GETTAG
HRESULT bCap_CommandRelease(int fd, uint32_t *hCommand)
int int32_t
HRESULT bCap_CommandPutTag(int fd, uint32_t hCommand, VARIANT newVal)
HRESULT bCap_VariableGetValue(int fd, uint32_t hVariable, VARIANT *pVal)
HRESULT bCap_MessageGetSerialNumber(int fd, uint32_t hMessage, int32_t *pVal)
#define ID_FILE_DELETE
HRESULT bCap_FileExecute(int fd, uint32_t hFile, BSTR bstrCommand, VARIANT vntParam, VARIANT *pVal)
bool getParam(const std::string &key, std::string &s) const
HRESULT bCap_RobotRotate(int fd, uint32_t hRobot, VARIANT vntRotSuf, float fDeg, VARIANT vntPivot, BSTR bstrOption)
HRESULT bCap_Close_Client(int *pfd)
#define ID_MESSAGE_GETNUMBER
#define ID_TASK_GETHELP
HRESULT bCap_FileRun(int fd, uint32_t hFile, BSTR bstrOption, BSTR *pVal)
#define ID_CONTROLLER_GETEXTENSION
HRESULT bCap_RobotSpeed(int fd, uint32_t hRobot, int32_t lAxis, float fSpeed)
#define ID_CONTROLLER_GETHELP
HRESULT bCap_GetRetry(int fd, unsigned int *retry)
#define ID_MESSAGE_GETDESTINATION
HRESULT bCap_GetTimeout(int fd, uint32_t *timeout)
HRESULT bCap_ControllerGetRobotNames(int fd, uint32_t hController, BSTR bstrOption, VARIANT *pVal)
HRESULT bCap_FileGetPath(int fd, uint32_t hFile, BSTR *pVal)
#define ID_COMMAND_PUTTIMEOUT
HRESULT bCap_TaskDelete(int fd, uint32_t hTask, BSTR bstrOption)
#define ID_COMMAND_GETTAG
#define ID_CONTROLLER_GETTASK
#define ID_CONTROLLER_GETROBOT
HRESULT bCap_RobotChange(int fd, uint32_t hRobot, BSTR bstrName)
#define ID_EXTENSION_GETHELP
#define ID_ROBOT_MOVE
HRESULT bCap_TaskGetAttribute(int fd, uint32_t hTask, int32_t *pVal)
HRESULT bCap_CommandPutTimeout(int fd, uint32_t hCommand, int32_t newVal)
HRESULT bCap_FileGetFileNames(int fd, uint32_t hFile, BSTR bstrOption, VARIANT *pVal)
#define ID_COMMAND_GETID
#define ID_CONTROLLER_GETATTRIBUTE
HRESULT bCap_ControllerPutTag(int fd, uint32_t hController, VARIANT newVal)
#define ID_EXTENSION_EXECUTE
#define ID_CONTROLLER_GETVARIABLENAMES
#define ID_ROBOT_HALT
uint32_t get_Timeout() const
#define ID_CONTROLLER_GETCOMMANDNAMES
#define ID_VARIABLE_GETTAG
#define ID_COMMAND_CANCEL
HRESULT bCap_FileGetValue(int fd, uint32_t hFile, VARIANT *pVal)
#define ID_TASK_EXECUTE
#define ID_CONTROLLER_GETFILE
#define ID_COMMAND_GETHELP
#define ID_ROBOT_CHUCK
HRESULT bCap_RobotGetVariableNames(int fd, uint32_t hRobot, BSTR bstrOption, VARIANT *pVal)
#define ID_COMMAND_PUTPARAMETERS
#define ID_FILE_COPY
HRESULT bCap_MessageGetDescription(int fd, uint32_t hMessage, BSTR *pVal)
HRESULT bCap_ExtensionGetID(int fd, uint32_t hExtension, VARIANT *pVal)
HRESULT bCap_MessageGetNumber(int fd, uint32_t hMessage, int32_t *pVal)
#define ID_ROBOT_GETID
HRESULT bCap_ControllerGetRobot(int fd, uint32_t hController, BSTR bstrName, BSTR bstrOption, uint32_t *hRobot)
#define ID_TASK_GETNAME
#define ID_FILE_GETVARIABLE
#define ID_CONTROLLER_GETID
#define ID_FILE_GETATTRIBUTE
#define ROS_ERROR(...)
#define ID_COMMAND_PUTTAG
HRESULT bCap_FileGetDateLastAccessed(int fd, uint32_t hFile, VARIANT *pVal)
HRESULT bCap_ControllerDisconnect(int fd, uint32_t *hController)
HRESULT bCap_MessageGetDestination(int fd, uint32_t hMessage, BSTR *pVal)
HRESULT bCap_VariableGetDateTime(int fd, uint32_t hVariable, VARIANT *pVal)
void put_Retry(unsigned int value)
HRESULT bCap_ExtensionGetName(int fd, uint32_t hExtension, BSTR *pVal)
HRESULT bCap_MessageGetDateTime(int fd, uint32_t hMessage, VARIANT *pVal)
#define ID_CONTROLLER_GETEXTENSIONNAMES
HRESULT bCap_FileRelease(int fd, uint32_t *hFile)
#define ID_VARIABLE_GETID
#define ID_EXTENSION_GETVARIABLENAMES
HRESULT bCap_ExtensionPutTag(int fd, uint32_t hExtension, VARIANT newVal)
#define ID_VARIABLE_PUTID
HRESULT bCap_TaskGetVariableNames(int fd, uint32_t hTask, BSTR bstrOption, VARIANT *pVal)
HRESULT bCap_FileGetSize(int fd, uint32_t hFile, int32_t *pVal)
#define ID_ROBOT_GOHOME
#define ID_CONTROLLER_GETVARIABLE
#define ID_ROBOT_RELEASE
HRESULT bCap_TaskGetFileName(int fd, uint32_t hTask, BSTR *pVal)
const std::string & get_Type() const
HRESULT bCap_TaskStart(int fd, uint32_t hTask, int32_t lMode, BSTR bstrOption)
HRESULT bCap_RobotGetTag(int fd, uint32_t hRobot, VARIANT *pVal)
#define ID_COMMAND_EXECUTE
HRESULT bCap_ExtensionGetVariable(int fd, uint32_t hExtension, BSTR bstrName, BSTR bstrOption, uint32_t *hVariable)


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