ypkt_lin.c
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * $Id: ypkt_lin.c 29340 2017-11-29 10:42:47Z seb $
4  *
5  * OS-specific USB packet layer, Linux version
6  *
7  * - - - - - - - - - License information: - - - - - - - - -
8  *
9  * Copyright (C) 2011 and beyond by Yoctopuce Sarl, Switzerland.
10  *
11  * Yoctopuce Sarl (hereafter Licensor) grants to you a perpetual
12  * non-exclusive license to use, modify, copy and integrate this
13  * file into your software for the sole purpose of interfacing
14  * with Yoctopuce products.
15  *
16  * You may reproduce and distribute copies of this file in
17  * source or object form, as long as the sole purpose of this
18  * code is to interface with Yoctopuce products. You must retain
19  * this notice in the distributed source file.
20  *
21  * You should refer to Yoctopuce General Terms and Conditions
22  * for additional information regarding your rights and
23  * obligations.
24  *
25  * THE SOFTWARE AND DOCUMENTATION ARE PROVIDED "AS IS" WITHOUT
26  * WARRANTY OF ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING
27  * WITHOUT LIMITATION, ANY WARRANTY OF MERCHANTABILITY, FITNESS
28  * FOR A PARTICULAR PURPOSE, TITLE AND NON-INFRINGEMENT. IN NO
29  * EVENT SHALL LICENSOR BE LIABLE FOR ANY INCIDENTAL, SPECIAL,
30  * INDIRECT OR CONSEQUENTIAL DAMAGES, LOST PROFITS OR LOST DATA,
31  * COST OF PROCUREMENT OF SUBSTITUTE GOODS, TECHNOLOGY OR
32  * SERVICES, ANY CLAIMS BY THIRD PARTIES (INCLUDING BUT NOT
33  * LIMITED TO ANY DEFENSE THEREOF), ANY CLAIMS FOR INDEMNITY OR
34  * CONTRIBUTION, OR OTHER SIMILAR COSTS, WHETHER ASSERTED ON THE
35  * BASIS OF CONTRACT, TORT (INCLUDING NEGLIGENCE), BREACH OF
36  * WARRANTY, OR OTHERWISE.
37  *
38  *********************************************************************/
39 
40 #define __FILE_ID__ "ypkt_lin"
41 #include "yapi.h"
42 #ifdef LINUX_API
43 #include "yproto.h"
44 #include <pthread.h>
45 #include <sys/types.h>
46 #include <sys/stat.h>
47 #include <fcntl.h>
48 #include <unistd.h>
49 
50 #define yLinSetErr(intro, err,errmsg) yLinSetErrEx(__LINE__,intro, err,errmsg)
51 
52 static int yLinSetErrEx(u32 line,char *intro, int err,char *errmsg)
53 {
54  const char *msg;
55  if(errmsg==NULL)
56  return YAPI_IO_ERROR;
57  switch(err){
58  case LIBUSB_SUCCESS: msg="Success (no error)";break;
59  case LIBUSB_ERROR_IO: msg="Input/output error"; break;
60  case LIBUSB_ERROR_INVALID_PARAM:msg="Invalid parameter"; break;
61  case LIBUSB_ERROR_ACCESS: msg="Access denied (insufficient permissions)"; break;
62  case LIBUSB_ERROR_NO_DEVICE: msg="No such device (it may have been disconnected)"; break;
63  case LIBUSB_ERROR_NOT_FOUND: msg="Entity not found"; break;
64  case LIBUSB_ERROR_BUSY: msg="Resource busy"; break;
65  case LIBUSB_ERROR_TIMEOUT: msg="Operation timed out"; break;
66  case LIBUSB_ERROR_OVERFLOW: msg="Overflow"; break;
67  case LIBUSB_ERROR_PIPE: msg="Pipe error"; break;
68  case LIBUSB_ERROR_INTERRUPTED: msg="System call interrupted (perhaps due to signal)"; break;
69  case LIBUSB_ERROR_NO_MEM: msg="Insufficient memory"; break;
70  case LIBUSB_ERROR_NOT_SUPPORTED:msg="Operation not supported or unimplemented on this platform"; break;
71  default:
72  case LIBUSB_ERROR_OTHER: msg="Other error"; break;
73  }
74  if (intro){
75  YSPRINTF(errmsg,YOCTO_ERRMSG_LEN,"%s:%s",intro,msg);
76  } else{
77  YSPRINTF(errmsg,YOCTO_ERRMSG_LEN,"LIN(%d):%s",line,msg);
78  }
79  HALLOG("LIN(%d):%s\n",line,msg);
80  return YAPI_IO_ERROR;
81 };
82 
83 
84  /*****************************************************************
85  * USB ENUMERATION
86 *****************************************************************/
87 
88 
89 #define YOCTO_LOCK_PIPE "/tmp/.yoctolock"
90 
91 int pid_lock_fd = -1;
92 
93 
94 // return 1 if we can reserve access to the device 0 if the device
95 // is already reserved
96 static int yReserveGlobalAccess(yContextSt *ctx, char *errmsg)
97 {
98  int fd;
99  int chk_val, mypid, usedpid = 0;
100  size_t res;
101  mode_t mode = 0666;
102  mode_t oldmode = umask(0000);
103  char msg[YOCTO_ERRMSG_LEN];
104 
105  HALLOG("old mode (%#o)\n",oldmode);
106  HALLOG("create fifo with (%#o)\n",mode);
107  if(mkfifo(YOCTO_LOCK_PIPE,mode)<0) {
108  HALLOG("unable to create lock fifo (%d:%s)\n",errno,strerror(errno));
109  }
110  umask(oldmode);
111  fd = open(YOCTO_LOCK_PIPE,O_RDWR|O_NONBLOCK);
112  if(fd<0){
113  HALLOG("unable to open lock fifo (%d)\n",errno);
114  if(errno==EACCES) {
115  return YERRMSG(YAPI_DOUBLE_ACCES, "we do not have acces to lock fifo");
116  }else{
117  // we cannot open lock file so we cannot realy
118  // check double instance so we asume that we are
119  // alone
120  return YAPI_SUCCESS;
121  }
122  }
123  chk_val = 0;
124  mypid = (int) getpid();
125  res = read(fd, &chk_val, sizeof(chk_val));
126  if (res == sizeof(chk_val)) {
127  //there is allready someone
128  usedpid = chk_val;
129  } else{
130  // nobody there -> store my PID
131  chk_val = mypid;
132  }
133  res = write(fd, &chk_val, sizeof(chk_val));
134  if(res != sizeof(chk_val)) {
135  YSPRINTF(msg, YOCTO_ERRMSG_LEN, "Write to lock fifo failed (%d)", res);
136  close(fd);
137  return YERRMSG(YAPI_DOUBLE_ACCES, msg);
138  }
139  if (usedpid != 0) {
140  if (usedpid == 1) {
141  close(fd);
142  // locked by api that not store the pid
143  return YERRMSG(YAPI_DOUBLE_ACCES, "Another process is already using yAPI");
144  } else {
145  YSPRINTF(msg, YOCTO_ERRMSG_LEN, "Another process (pid %d) is already using yAPI", (u32) usedpid);
146  close(fd);
147  return YERRMSG(YAPI_DOUBLE_ACCES, msg);
148  }
149  }
150  pid_lock_fd = fd;
151  return YAPI_SUCCESS;
152 }
153 
154 
155 size_t dropwarning;
156 
157 static void yReleaseGlobalAccess(yContextSt *ctx)
158 {
159  int chk_val;
160  if(pid_lock_fd >=0){
161  dropwarning = read(pid_lock_fd,&chk_val,sizeof(chk_val));
162  close(pid_lock_fd);
163  pid_lock_fd = -1;
164  }
165 }
166 
167 typedef struct {
168  libusb_device *dev;
169  int desc_index;
170  int len;
171  char *string;
172  u64 expiration;
173 } stringCacheSt;
174 
175 #define STRING_CACHE_SIZE 16
176 #define STRING_CACHE_EXPIRATION 60000 //1 minutes
177 static stringCacheSt stringCache[STRING_CACHE_SIZE];
178 
179 
180 // on success data point to a null terminated string of max length-1 characters
181 static int getUsbStringASCII(yContextSt *ctx, libusb_device_handle *hdl, libusb_device *dev, u8 desc_index, char *data, u32 length)
182 {
183  u8 buffer[512];
184  u32 l,len;
185  int res,i;
186  stringCacheSt *c = stringCache;
187  stringCacheSt *f = NULL;
188  u64 now = yapiGetTickCount();
189 
190  yEnterCriticalSection(&ctx->string_cache_cs);
191 
192  for (i = 0; i < STRING_CACHE_SIZE; i++, c++) {
193  if (c->expiration > now) {
194  if(c->dev == dev && c->desc_index == desc_index) {
195  if (c->len > 0 && c->string) {
196  len = c->len;
197  if (c->len >= length)
198  len = length-1;
199  memcpy(data, c->string, len);
200  data[len] = 0;
201  HALENUMLOG("return string from cache (%p:%d->%s)\n",dev,desc_index,c->string);
202  yLeaveCriticalSection(&ctx->string_cache_cs);
203  return c->len;
204  } else {
205  f = c;
206  break;
207  }
208  }
209  } else {
210  if (c->string) {
211  yFree(c->string);
212  c->string =NULL;
213  }
214  if (f == NULL) {
215  f = c;
216  }
217  }
218  }
219 
220  res=libusb_control_transfer(hdl, LIBUSB_ENDPOINT_IN,
221  LIBUSB_REQUEST_GET_DESCRIPTOR, (LIBUSB_DT_STRING << 8) | desc_index,
222  0, buffer, 512, 10000);
223  if(res<0) {
224  yLeaveCriticalSection(&ctx->string_cache_cs);
225  return res;
226  }
227 
228  len=(buffer[0]-2)/2;
229  if (len >= length) {
230  len = length - 1;
231  }
232 
233  for (l = 0; l < len; l++){
234  data[l] = (char) buffer[2+(l*2)];
235  }
236  data[len] = 0;
237 
238  if (f != NULL) {
239  f->dev = dev;
240  f->desc_index = desc_index;
241  f->string = yMalloc(len+1);
242  memcpy(f->string, data, len+1);
243  f->len = len;
244  f->expiration = yapiGetTickCount() + STRING_CACHE_EXPIRATION;
245  HALENUMLOG("add string to cache (%p:%d->%s)\n",dev,desc_index,f->string);
246  }
247  yLeaveCriticalSection(&ctx->string_cache_cs);
248 
249  return len;
250 }
251 
252 
253 int process_libusb_events(yContextSt *ctx, int ms, char * errmsg)
254 {
255  int res;
256  struct timeval tv;
257  memset(&tv, 0, sizeof(tv));
258  tv.tv_sec = ms / 1000;
259  tv.tv_usec = (ms % 1000) * 1000;
260  res = libusb_handle_events_timeout(ctx->libusb, &tv);
261  if (res < 0) {
262  yLinSetErr("libusb_handle_events_timeout", res, errmsg);
263  }
264  return res;
265 }
266 
267 
268 static void *event_thread(void *param)
269 {
270  yContextSt *ctx = (yContextSt*)param;
271  char errmsg[YOCTO_ERRMSG_LEN];
272  ctx->usb_thread_state = USB_THREAD_RUNNING;
273  /* Non-blocking. See if the OS has any reports to give. */
274  HALLOG("Start event_thread run loop\n");
275  while (ctx->usb_thread_state != USB_THREAD_MUST_STOP) {
276  int res = process_libusb_events(ctx, 1000, errmsg);
277  if (res < 0) {
278  yLinSetErr("libusb_handle_events_timeout", res,errmsg);
279  break;
280  }
281  }
282  HALLOG("event_thread run loop stoped\n");
283  ctx->usb_thread_state = USB_THREAD_STOPED;
284  return NULL;
285 }
286 
287 
288 int yyyUSB_init(yContextSt *ctx,char *errmsg)
289 {
290  int res;
291 
292  YPROPERR(yReserveGlobalAccess(ctx, errmsg));
293  memset(stringCache, 0, sizeof(stringCache));
294  yInitializeCriticalSection(&ctx->string_cache_cs);
295  res = libusb_init(&ctx->libusb);
296  if(res !=0){
297  return yLinSetErr("Unable to start lib USB", res,errmsg);
298  }
299 #if 0
300  {
301  const struct libusb_version *libusb_v;
302  libusb_v = libusb_get_version();
303  dbglog("Use libUSB v%d.%d.%d.%d\n", libusb_v->major, libusb_v->minor, libusb_v->micro, libusb_v->nano);
304  }
305 #endif
306  ctx->usb_thread_state = USB_THREAD_NOT_STARTED;
307  pthread_create(&ctx->usb_thread, NULL, event_thread, ctx);
308  //wait thead start
309  while(ctx->usb_thread_state != USB_THREAD_RUNNING){
310  usleep(50000);
311  }
312 
313  return YAPI_SUCCESS;
314 }
315 
316 
317 int yyyUSB_stop(yContextSt *ctx,char *errmsg)
318 {
319  int i;
320  stringCacheSt *c = stringCache;
321 
322  if(ctx->usb_thread_state == USB_THREAD_RUNNING){
323  ctx->usb_thread_state = USB_THREAD_MUST_STOP;
324  pthread_join(ctx->usb_thread,NULL);
325  }
326  YASSERT(ctx->usb_thread_state == USB_THREAD_STOPED);
327 
328  libusb_exit(ctx->libusb);
329  yReleaseGlobalAccess(ctx);
330  for (i = 0; i < STRING_CACHE_SIZE; i++, c++) {
331  if(c->string) {
332  yFree(c->string);
333  }
334  }
335  yDeleteCriticalSection(&ctx->string_cache_cs);
336 
337  return YAPI_SUCCESS;
338 }
339 
340 
341 
342 static int getDevConfig(libusb_device *dev, struct libusb_config_descriptor **config)
343 {
344 
345  int res = libusb_get_active_config_descriptor(dev, config);
346  if(res==LIBUSB_ERROR_NOT_FOUND){
347  HALLOG("not yet configured\n");
348  if(libusb_get_config_descriptor(dev, 0, config)!=0){
349  return -1;
350  }
351  }else if(res!=0){
352  HALLOG("unable to get active configuration %d\n",res);
353  return -1;
354  }
355  return 0;
356 
357 }
358 
359 
360 int yyyUSBGetInterfaces(yInterfaceSt **ifaces,int *nbifaceDetect,char *errmsg)
361 {
362  libusb_device **list;
363  ssize_t nbdev;
364  int returnval=YAPI_SUCCESS;
365  int i;
366  int alloc_size;
367  yInterfaceSt *iface;
368 
369  nbdev = libusb_get_device_list(yContext->libusb,&list);
370  if (nbdev < 0)
371  return yLinSetErr("Unable to get device list", nbdev, errmsg);
372  HALENUMLOG("%d devices found\n",nbdev);
373 
374  // allocate buffer for detected interfaces
375  *nbifaceDetect = 0;
376  alloc_size = (nbdev + 1) * sizeof(yInterfaceSt);
377  *ifaces = (yInterfaceSt*) yMalloc(alloc_size);
378  memset(*ifaces, 0, alloc_size);
379 
380  for (i = 0; i < nbdev; i++) {
381  int res;
382  struct libusb_device_descriptor desc;
383  struct libusb_config_descriptor *config;
384  libusb_device_handle *hdl;
385 
386  libusb_device *dev = list[i];
387  if ((res = libusb_get_device_descriptor(dev,&desc)) != 0){
388  returnval = yLinSetErr("Unable to get device descriptor",res,errmsg);
389  goto exit;
390  }
391  if (desc.idVendor != YOCTO_VENDORID) {
392  continue;
393  }
394  HALENUMLOG("open device %x:%x\n", desc.idVendor, desc.idProduct);
395 
396  if(getDevConfig(dev, &config) < 0) {
397  continue;
398  }
399  iface = (*ifaces) + (*nbifaceDetect);
400  iface->vendorid = (u16)desc.idVendor;
401  iface->deviceid = (u16)desc.idProduct;
402  iface->ifaceno = 0;
403  iface->devref = libusb_ref_device(dev);
404  res = libusb_open(dev, &hdl);
405  if (res == LIBUSB_ERROR_ACCESS) {
406  returnval = YERRMSG(YAPI_IO_ERROR, "the user has insufficient permissions to access USB devices");
407  goto exit;
408  }
409  if (res != 0){
410  HALENUMLOG("unable to access device %x:%x\n", desc.idVendor, desc.idProduct);
411  continue;
412  }
413  HALENUMLOG("try to get serial for %x:%x:%x (%p)\n", desc.idVendor, desc.idProduct, desc.iSerialNumber, dev);
414  res = getUsbStringASCII(yContext, hdl, dev, desc.iSerialNumber, iface->serial, YOCTO_SERIAL_LEN);
415  if (res < 0) {
416  HALENUMLOG("unable to get serial for device %x:%x\n", desc.idVendor, desc.idProduct);
417  }
418  libusb_close(hdl);
419  (*nbifaceDetect)++;
420  HALENUMLOG("----Running Dev %x:%x:%d:%s ---\n", iface->vendorid, iface->deviceid, iface->ifaceno, iface->serial);
421  libusb_free_config_descriptor(config);
422  }
423 
424 exit:
425  libusb_free_device_list(list,1);
426  return returnval;
427 
428 }
429 
430 
431 
432 // return 1 if OS hdl are identicals
433 // 0 if any of the interface has changed
434 int yyyOShdlCompare( yPrivDeviceSt *dev, yInterfaceSt *newiface)
435 {
436  if(dev->infos.nbinbterfaces != 1){
437  HALLOG("bad number of inteface for %s (%d)\n",dev->infos.serial,dev->infos.nbinbterfaces);
438  return 0;
439  }
440  if(dev->iface.devref != newiface->devref){
441  HALLOG("devref has changed for %s (%X)\n",dev->infos.serial,dev->iface.devref);
442  return 0;
443  }
444 
445  return 1;
446 }
447 
448 static void rd_callback(struct libusb_transfer *transfer);
449 static void wr_callback(struct libusb_transfer *transfer);
450 
451 
452 static int sendNextPkt(yInterfaceSt *iface, char *errmsg)
453 {
454  pktItem *pktitem;
455  yPktQueuePeekH2D(iface, &pktitem);
456  if (pktitem != NULL) {
457  int res;
458  memcpy(&iface->wrTr->tmppkt, &pktitem->pkt, sizeof(USB_Packet));
459  libusb_fill_interrupt_transfer( iface->wrTr->tr,
460  iface->hdl,
461  iface->wrendp,
462  (u8*)&iface->wrTr->tmppkt,
463  sizeof(USB_Packet),
464  wr_callback,
465  iface->wrTr,
466  2000);
467  res = libusb_submit_transfer(iface->wrTr->tr);
468  if (res < 0) {
469  return yLinSetErr("libusb_submit_transfer(WR) failed", res, errmsg);
470  }
471  }
472  return YAPI_SUCCESS;
473 }
474 
475 
476 static int submitReadPkt(yInterfaceSt *iface, char *errmsg)
477 {
478  int res;
479  libusb_fill_interrupt_transfer( iface->rdTr->tr,
480  iface->hdl,
481  iface->rdendp,
482  (u8*)&iface->rdTr->tmppkt,
483  sizeof(USB_Packet),
484  rd_callback,
485  iface->rdTr,
486  0);
487  res = libusb_submit_transfer(iface->rdTr->tr);
488  if (res < 0) {
489  return yLinSetErr("libusb_submit_transfer(RD) failed", res, errmsg);
490  }
491  return YAPI_SUCCESS;
492 }
493 
494 
495 static void rd_callback(struct libusb_transfer *transfer)
496 {
497  int res;
498  linRdTr *lintr = (linRdTr*)transfer->user_data;
499  yInterfaceSt *iface = lintr->iface;
500  char errmsg[YOCTO_ERRMSG_LEN];
501 
502  if (lintr == NULL){
503  HALLOG("CBrd:drop invalid ypkt rd_callback (lintr is null)\n");
504  return;
505  }
506  if (iface == NULL){
507  HALLOG("CBrd:drop invalid ypkt rd_callback (iface is null)\n");
508  return;
509  }
510 
511  switch(transfer->status){
512  case LIBUSB_TRANSFER_COMPLETED:
513  //HALLOG("%s:%d pkt_arrived (len=%d)\n",iface->serial,iface->ifaceno,transfer->actual_length);
514  yPktQueuePushD2H(iface,&lintr->tmppkt,NULL);
515  break;
516  case LIBUSB_TRANSFER_ERROR:
517  iface->ioError++;
518  HALLOG("CBrd:%s pkt error (len=%d nbError:%d)\n",iface->serial, transfer->actual_length, iface->ioError);
519  break;
520  case LIBUSB_TRANSFER_TIMED_OUT :
521  HALLOG("CBrd:%s pkt timeout\n",iface->serial);
522  break;
523  case LIBUSB_TRANSFER_CANCELLED:
524  HALLOG("CBrd:%s pkt_cancelled (len=%d) \n",iface->serial, transfer->actual_length);
525  if (iface->flags.yyySetupDone && transfer->actual_length == 64) {
526  yPktQueuePushD2H(iface, &lintr->tmppkt, NULL);
527  }
528  return;
529  case LIBUSB_TRANSFER_STALL:
530  HALLOG("CBrd:%s pkt stall\n",iface->serial );
531  res = libusb_cancel_transfer(lintr->tr);
532  HALLOG("CBrd:%s libusb_cancel_transfer returned %d\n",iface->serial, res);
533  res = libusb_clear_halt(iface->hdl, iface->rdendp);
534  HALLOG("CBrd:%s libusb_clear_hal returned %d\n",iface->serial, res);
535  break;
536  case LIBUSB_TRANSFER_NO_DEVICE:
537  HALLOG("CBrd:%s no_device (len=%d)\n",iface->serial, transfer->actual_length);
538  return;
539  case LIBUSB_TRANSFER_OVERFLOW:
540  HALLOG("CBrd:%s pkt_overflow (len=%d)\n",iface->serial, transfer->actual_length);
541  return;
542  default:
543  HALLOG("CBrd:%s unknown state %X\n",iface->serial, transfer->status);
544  return;
545  }
546 
547  if (iface->flags.yyySetupDone) {
548  res = submitReadPkt(iface, errmsg);
549  if (res < 0) {
550  HALLOG("CBrd:%s libusb_submit_transfer errror %X\n", iface->serial, res);
551  }
552  }
553 
554 }
555 
556 static void wr_callback(struct libusb_transfer *transfer)
557 {
558  linRdTr *lintr = (linRdTr*)transfer->user_data;
559  yInterfaceSt *iface = lintr->iface;
560  char errmsg[YOCTO_ERRMSG_LEN];
561  pktItem *pktitem;
562  int res;
563 
564  if (lintr == NULL) {
565  HALLOG("CBwr:drop invalid ypkt wr_callback (lintr is null)\n");
566  return;
567  }
568 
569  if (iface == NULL){
570  HALLOG("CBwr:drop invalid ypkt wr_callback (iface is null)\n");
571  return;
572  }
573  YASSERT(transfer == lintr->tr);
574 
575  switch(transfer->status) {
576  case LIBUSB_TRANSFER_COMPLETED:
577  //HALLOG("CBwr:%s pkt_sent (len=%d)\n",iface->serial, transfer->actual_length);
578  // remove sent packet
579  yPktQueuePopH2D(iface, &pktitem);
580  yFree(pktitem);
581  res = sendNextPkt(iface, errmsg);
582  if (res < 0) {
583  HALLOG("send of next pkt item failed:%d:%s\n", res, errmsg);
584  }
585  return;
586  case LIBUSB_TRANSFER_ERROR:
587  iface->ioError++;
588  HALLOG("CBwr:%s pkt error (len=%d nbError:%d)\n",iface->serial, transfer->actual_length, iface->ioError);
589  break;
590  case LIBUSB_TRANSFER_TIMED_OUT :
591  HALLOG("CBwr:%s pkt timeout\n",iface->serial);
592  res = sendNextPkt(iface, errmsg);
593  if (res < 0) {
594  HALLOG("retry of next pkt item failed:%d:%s\n", res, errmsg);
595  }
596  break;
597  case LIBUSB_TRANSFER_CANCELLED:
598  HALLOG("CBwr:%s pkt_cancelled (len=%d) \n",iface->serial, transfer->actual_length);
599  break;
600  case LIBUSB_TRANSFER_STALL:
601  HALLOG("CBwr:%s pkt stall\n",iface->serial );
602  break;
603  case LIBUSB_TRANSFER_NO_DEVICE:
604  HALLOG("CBwr:%s pkt_cancelled (len=%d)\n",iface->serial, transfer->actual_length);
605  return;
606  case LIBUSB_TRANSFER_OVERFLOW:
607  HALLOG("CBwr:%s pkt_overflow (len=%d)\n",iface->serial, transfer->actual_length);
608  break;
609  default:
610  HALLOG("CBwr:%s unknown state %X\n",iface->serial, transfer->status);
611  break;
612  }
613 }
614 
615 
616 int yyySetup(yInterfaceSt *iface,char *errmsg)
617 {
618  int res,j;
619  int error;
620  struct libusb_config_descriptor *config;
621  const struct libusb_interface_descriptor* ifd;
622 
623 
624 
625  HALLOG("%s yyySetup %X:%X\n",iface->serial,iface->vendorid,iface->deviceid);
626  if(iface->devref==NULL){
627  return YERR(YAPI_DEVICE_NOT_FOUND);
628  }
629 
630  // we need to do this as it is possible that the device was not closed properly in a previous session
631  // if we don't do this and the device wasn't closed properly odd behavior results.
632  // thanks to Rob Krakora who find this solution
633  if((res=libusb_open(iface->devref,&iface->hdl))!=0){
634  return yLinSetErr("libusb_open", res,errmsg);
635  } else {
636  libusb_reset_device(iface->hdl);
637  libusb_close(iface->hdl);
638  usleep(200);
639  }
640 
641  if((res=libusb_open(iface->devref,&iface->hdl))!=0){
642  return yLinSetErr("libusb_open", res,errmsg);
643  }
644 
645  if((res=libusb_kernel_driver_active(iface->hdl,iface->ifaceno))<0){
646  error= yLinSetErr("libusb_kernel_driver_active",res,errmsg);
647  goto error;
648  }
649  if (res) {
650  HALLOG("%s need to detach kernel driver\n",iface->serial);
651  if((res = libusb_detach_kernel_driver(iface->hdl,iface->ifaceno))<0){
652  error= yLinSetErr("libusb_detach_kernel_driver",res,errmsg);
653  goto error;
654  }
655  }
656 
657  HALLOG("%s Claim interface\n",iface->serial);
658  if((res = libusb_claim_interface(iface->hdl,iface->ifaceno))<0){
659  error= yLinSetErr("libusb_claim_interface", res,errmsg);
660  goto error;
661  }
662 
663 
664  res=getDevConfig(iface->devref,&config);
665  if(res<0){
666  error=YERRMSG(YAPI_IO_ERROR,"unable to get configuration descriptor");
667  goto error;
668  }
669 
670 
671  ifd = &config->interface[iface->ifaceno].altsetting[0];
672  for (j = 0; j < ifd->bNumEndpoints; j++) {
673  //HALLOG("endpoint %X size=%d \n",ifd->endpoint[j].bEndpointAddress,ifd->endpoint[j].wMaxPacketSize);
674  if((ifd->endpoint[j].bEndpointAddress & LIBUSB_ENDPOINT_DIR_MASK) == LIBUSB_ENDPOINT_IN){
675  iface->rdendp = ifd->endpoint[j].bEndpointAddress;
676  }else{
677  iface->wrendp = ifd->endpoint[j].bEndpointAddress;
678  }
679  }
680  HALLOG("ednpoints are rd=%d wr=%d\n", iface->rdendp,iface->wrendp);
681 
682  yPktQueueInit(&iface->rxQueue);
683  yPktQueueInit(&iface->txQueue);
684  iface->rdTr = yMalloc(sizeof(linRdTr));
685  iface->wrTr = yMalloc(sizeof(linRdTr));
686  HALLOG("allocate linRdTr=%p linWrTr\n", iface->rdTr, iface->wrTr);
687  iface->wrTr->iface = iface;
688  iface->wrTr->tr = libusb_alloc_transfer(0);
689  iface->rdTr->iface = iface;
690  iface->rdTr->tr = libusb_alloc_transfer(0);
691  iface->flags.yyySetupDone = 1;
692  HALLOG("%s both libusbTR allocated (%p /%p)\n",iface->serial, iface->rdTr->tr, iface->wrTr->tr);
693  res = submitReadPkt(iface, errmsg);
694  if (res < 0) {
695  return res;
696  }
697  HALLOG("%s yyySetup done\n",iface->serial);
698 
699  return YAPI_SUCCESS;
700 error:
701  libusb_close(iface->hdl);
702  return error;
703 }
704 
705 
706 
707 
708 int yyySignalOutPkt(yInterfaceSt *iface, char *errmsg)
709 {
710  return sendNextPkt(iface, errmsg);
711 }
712 
713 
714 
715 void yyyPacketShutdown(yInterfaceSt *iface)
716 {
717  if (iface && iface->hdl) {
718  int res;
719  iface->flags.yyySetupDone = 0;
720  HALLOG("%s:%d cancel all transfer\n",iface->serial,iface->ifaceno);
721  if (iface->rdTr->tr) {
722  int count = 10;
723  int res =libusb_cancel_transfer(iface->rdTr->tr);
724  if(res == 0){
725  while(count && iface->rdTr->tr->status != LIBUSB_TRANSFER_CANCELLED){
726  usleep(1000);
727  count--;
728  }
729  }
730  }
731  HALLOG("%s:%d libusb relase iface\n",iface->serial,iface->ifaceno);
732  res = libusb_release_interface(iface->hdl,iface->ifaceno);
733  if(res != 0 && res!=LIBUSB_ERROR_NOT_FOUND && res!=LIBUSB_ERROR_NO_DEVICE){
734  HALLOG("%s:%dlibusb_release_interface error\n",iface->serial,iface->ifaceno);
735  }
736 
737  res = libusb_attach_kernel_driver(iface->hdl,iface->ifaceno);
738  if(res<0 && res!=LIBUSB_ERROR_NO_DEVICE){
739  HALLOG("%s:%d libusb_attach_kernel_driver error\n",iface->serial,iface->ifaceno);
740  }
741  libusb_close(iface->hdl);
742  iface->hdl = NULL;
743 
744  if (iface->rdTr->tr) {
745  HALLOG("%s:%d libusb_TR free\n", iface->serial, iface->ifaceno);
746  libusb_free_transfer(iface->rdTr->tr);
747  iface->rdTr->tr = NULL;
748  }
749  yFree(iface->rdTr);
750  yPktQueueFree(&iface->rxQueue);
751  yPktQueueFree(&iface->txQueue);
752  }
753 }
754 
755 #endif
bool param(const std::string &param_name, T &param_val, const T &default_val)
#define YERRMSG(code, message)
Definition: yproto.h:458
void yInitializeCriticalSection(yCRITICAL_SECTION *cs)
Definition: ythread.c:629
f
USB_Packet pkt
Definition: yproto.h:508
yDeviceSt infos
Definition: yproto.h:689
yContextSt * yContext
Definition: ystream.c:59
#define YERR(code)
Definition: yproto.h:456
#define dbglog(args...)
Definition: yproto.h:413
#define YPROPERR(call)
Definition: yproto.h:455
int yyySetup(yInterfaceSt *iface, char *errmsg)
int yyyUSBGetInterfaces(yInterfaceSt **ifaces, int *nbifaceDetect, char *errmsg)
#define YOCTO_SERIAL_LEN
Definition: ydef.h:420
void yLeaveCriticalSection(yCRITICAL_SECTION *cs)
Definition: ythread.c:672
#define YOCTO_ERRMSG_LEN
Definition: ydef.h:418
YRETCODE yPktQueuePopH2D(yInterfaceSt *iface, pktItem **pkt)
Definition: ystream.c:1176
int yyyUSB_init(yContextSt *ctx, char *errmsg)
#define HALENUMLOG(fmt, args...)
Definition: yproto.h:310
int yyySignalOutPkt(yInterfaceSt *iface, char *errmsg)
pktQueue txQueue
Definition: yproto.h:572
int yyyUSB_stop(yContextSt *ctx, char *errmsg)
yInterfaceSt iface
Definition: yproto.h:698
pktQueue rxQueue
Definition: yproto.h:571
#define YASSERT(x)
Definition: yproto.h:454
#define YSPRINTF
Definition: yproto.h:238
YRETCODE yPktQueuePeekH2D(yInterfaceSt *iface, pktItem **pkt)
Definition: ystream.c:1160
#define YOCTO_VENDORID
Definition: ydef.h:402
u16 ifaceno
Definition: yproto.h:565
#define HALLOG(fmt, args...)
Definition: yproto.h:295
void yEnterCriticalSection(yCRITICAL_SECTION *cs)
Definition: ythread.c:647
#define yFree(ptr)
Definition: yproto.h:199
char serial[YOCTO_SERIAL_LEN *2]
Definition: yproto.h:567
u16 deviceid
Definition: yproto.h:564
#define yMalloc(size)
Definition: yproto.h:198
YRETCODE yPktQueuePushD2H(yInterfaceSt *iface, const USB_Packet *pkt, char *errmsg)
Definition: ystream.c:1097
void yDeleteCriticalSection(yCRITICAL_SECTION *cs)
Definition: ythread.c:682
void yPktQueueFree(pktQueue *q)
Definition: ystream.c:928
u64 YAPI_FUNCTION_EXPORT yapiGetTickCount(void)
Definition: yapi.c:2713
void yyyPacketShutdown(yInterfaceSt *iface)
struct _yInterfaceSt::@69 flags
char serial[YOCTO_SERIAL_LEN]
Definition: ydef.h:454
u16 nbinbterfaces
Definition: ydef.h:451
int yyyOShdlCompare(yPrivDeviceSt *dev, yInterfaceSt *newiface)
u32 yyySetupDone
Definition: yproto.h:569
void yPktQueueInit(pktQueue *q)
Definition: ystream.c:919
u16 vendorid
Definition: yproto.h:563


yoctopuce_altimeter
Author(s): Anja Sheppard
autogenerated on Mon Jun 10 2019 15:49:11