ypkt_osx.c
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * $Id: ypkt_osx.c 28024 2017-07-10 08:50:02Z mvuilleu $
4  *
5  * OS-specific USB packet layer, Mac OS X 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_osx"
41 #include "yapi.h"
42 #ifdef OSX_API
43 #include "yproto.h"
44 #include <sys/types.h>
45 #include <sys/stat.h>
46 #include <sys/sysctl.h>
47 #include <fcntl.h>
48 #include <unistd.h>
49 
50 /*****************************************************************
51  * USB ENUMERATION
52  *****************************************************************/
53 
54 
55 #define YOCTO_LOCK_PIPE "/tmp/.yoctolock"
56 
57 // return YAPI_SUCCESS if we can reserve access to the device return
58 // an error if the device is already reserved
59 static int yReserveGlobalAccess(yContextSt *ctx, char *errmsg)
60 {
61  int fd;
62  int chk_val, mypid, usedpid = 0;
63  size_t res;
64 
65  mkfifo(YOCTO_LOCK_PIPE, 0600);
66  fd = open(YOCTO_LOCK_PIPE, O_RDWR|O_NONBLOCK);
67  if (fd < 0) {
68  // we cannot open lock file so we cannot realy
69  // check double instance so we asume that we are
70  // alone
71  return YAPI_SUCCESS;
72  }
73  chk_val = 0;
74  mypid = (int) getpid();
75  res = read(fd, &chk_val, sizeof(chk_val));
76  if (res == sizeof(chk_val)) {
77  //there is allready someone
78  usedpid = chk_val;
79  } else{
80  // nobody there -> store my PID
81  chk_val = mypid;
82  }
83  write(fd, &chk_val, sizeof(chk_val));
84  if (usedpid != 0) {
85  if (usedpid == 1) {
86  // locked by api that not store the pid
87  return YERRMSG(YAPI_DOUBLE_ACCES, "Another process is already using yAPI");
88  } else {
89  char msg[YOCTO_ERRMSG_LEN];
90  YSPRINTF(msg, YOCTO_ERRMSG_LEN, "Another process (pid %d) is already using yAPI", (u32) usedpid);
91  return YERRMSG(YAPI_DOUBLE_ACCES, msg);
92  }
93  }
94  return YAPI_SUCCESS;
95 }
96 
97 
98 
99 static void yReleaseGlobalAccess(yContextSt *ctx)
100 {
101  int chk_val;
102  int fd = open(YOCTO_LOCK_PIPE,O_RDWR|O_NONBLOCK);
103  if(fd>=0){
104  read(fd,&chk_val,sizeof(chk_val));
105  }
106 }
107 
108 static void *event_thread(void *param)
109 {
110  yContextSt *ctx=param;
111 
112  ctx->usb_run_loop = CFRunLoopGetCurrent();
113  ctx->usb_thread_state = USB_THREAD_RUNNING;
114  /* Non-blocking. See if the OS has any reports to give. */
115  HALLOG("Start event_thread run loop\n");
116  while (ctx->usb_thread_state != USB_THREAD_MUST_STOP) {
117  CFRunLoopRunInMode( kCFRunLoopDefaultMode, 10, FALSE);
118  }
119 
120  HALLOG("event_thread run loop stoped\n");
121  ctx->usb_thread_state = USB_THREAD_STOPED;
122  return NULL;
123 }
124 
125 
126 static int setupHIDManager(yContextSt *ctx, OSX_HID_REF *hid, char *errmsg)
127 {
128  int c_vendorid = YOCTO_VENDORID;
129  CFMutableDictionaryRef dictionary;
130  CFNumberRef Vendorid;
131  IOReturn tIOReturn;
132 
133  yInitializeCriticalSection(&hid->hidMCS);
134  // Initialize HID Manager
135  hid->manager = IOHIDManagerCreate(kCFAllocatorDefault, kIOHIDOptionsTypeNone);
136  // create dictionary to match Yocto devices
137  dictionary = CFDictionaryCreateMutable(kCFAllocatorDefault,1,&kCFTypeDictionaryKeyCallBacks,&kCFTypeDictionaryValueCallBacks);
138  Vendorid = CFNumberCreate( kCFAllocatorDefault, kCFNumberIntType, &c_vendorid );
139  CFDictionarySetValue( dictionary, CFSTR( kIOHIDVendorIDKey ), Vendorid );
140  CFRelease(Vendorid);
141  // register the dictionary
142  IOHIDManagerSetDeviceMatching(hid->manager, dictionary );
143  // now we can release the dictionary
144  CFRelease(dictionary);
145  // sechedulle the HID Manager with our global run loop
146  IOHIDManagerScheduleWithRunLoop(hid->manager, ctx->usb_run_loop, kCFRunLoopDefaultMode);
147 
148  // Now open the IO HID Manager reference
149  tIOReturn = IOHIDManagerOpen(hid->manager, kIOHIDOptionsTypeNone );
150  if(kIOReturnSuccess != tIOReturn ||CFGetTypeID(hid->manager) != IOHIDManagerGetTypeID()){
151  HALLOG("Unable to Open HID Manager");
152  return YERRMSG(YAPI_NOT_SUPPORTED,"Unable to Open HID Manager");
153  }
154  return YAPI_SUCCESS;
155 
156 }
157 
158 
159 
160 static void stopHIDManager(OSX_HID_REF *hid)
161 {
162  if (hid->manager) {
163  IOHIDManagerClose(hid->manager, kIOHIDOptionsTypeNone );
164  CFRelease( hid->manager);
165  hid->manager=NULL;
166  yDeleteCriticalSection(&hid->hidMCS);
167  }
168 }
169 
170 
171 int yyyUSB_init(yContextSt *ctx,char *errmsg)
172 {
173  char str[256];
174  size_t size = sizeof(str);
175  YPROPERR(yReserveGlobalAccess(ctx, errmsg));
176 
177  if (sysctlbyname("kern.osrelease", str, &size, NULL, 0) ==0){
178  int numver;
179  //15.x.x OS X 10.11.x El Capitan
180  //14.x.x OS X 10.10.x Yosemite
181  //13.x.x OS X 10.9.x Mavericks
182  //12.x.x OS X 10.8.x Mountain Lion
183  //11.x.x OS X 10.7.x Lion
184  //10.x.x OS X 10.6.x Snow Leopard
185  str[2]=0;
186  numver = atoi(str);
187  if (numver >= 13 && numver < 15){
188  ctx->osx_flags |= YCTX_OSX_MULTIPLES_HID;
189  }
190  }
191 
192  ctx->usb_thread_state = USB_THREAD_NOT_STARTED;
193  pthread_create(&ctx->usb_thread, NULL, event_thread, ctx);
194  while(ctx->usb_thread_state != USB_THREAD_RUNNING){
195  usleep(50000);
196  }
197 
198  if (YISERR(setupHIDManager(ctx, &ctx->hid,errmsg))) {
199  return YAPI_IO_ERROR;
200  }
201  return YAPI_SUCCESS;
202 }
203 
204 
205 int yyyUSB_stop(yContextSt *ctx,char *errmsg)
206 {
207  stopHIDManager(&ctx->hid);
208 
209  if(ctx->usb_thread_state == USB_THREAD_RUNNING){
210  ctx->usb_thread_state = USB_THREAD_MUST_STOP;
211  CFRunLoopStop(ctx->usb_run_loop);
212  }
213  pthread_join(ctx->usb_thread,NULL);
214  YASSERT(ctx->usb_thread_state == USB_THREAD_STOPED);
215 
216  yReleaseGlobalAccess(ctx);
217 
218  return 0;
219 }
220 
221 
222 
223 
224 static u32 get_int_property(IOHIDDeviceRef device, CFStringRef key)
225 {
226  CFTypeRef ref;
227  u32 value;
228 
229  ref = IOHIDDeviceGetProperty(device, key);
230  if (ref) {
231  if (CFGetTypeID(ref) == CFNumberGetTypeID() && CFNumberGetValue((CFNumberRef) ref, kCFNumberSInt32Type, &value)) {
232  return value;
233  }
234  }
235  return 0;
236 }
237 
238 
239 static void get_txt_property(IOHIDDeviceRef device,char *buffer,u32 maxlen, CFStringRef key)
240 {
241  CFTypeRef ref;
242  size_t len;
243 
244  ref = IOHIDDeviceGetProperty(device, key);
245  if (ref) {
246  if (CFGetTypeID(ref) == CFStringGetTypeID()) {
247  const char *str;
248  CFStringEncoding encodingMethod;
249  encodingMethod = CFStringGetSystemEncoding();
250  // 1st try for English system
251  str = CFStringGetCStringPtr(ref, encodingMethod);
252  //str = NULL;
253  if ( str == NULL ) {
254  // 2nd try
255  encodingMethod = kCFStringEncodingUTF8;
256  str = CFStringGetCStringPtr(ref, encodingMethod);
257  }
258  if( str == NULL ) {
259  //3rd try
260  CFIndex cflength = CFStringGetLength(ref)*2+2;
261  char *tmp_str = yMalloc( (u32)cflength);
262  if (!CFStringGetCString(ref, tmp_str, cflength, kCFStringEncodingUTF8 )) {
263  yFree( tmp_str );
264  *buffer=0;
265  return;
266  }
267  if(cflength>maxlen-1){
268  cflength=maxlen-1;
269  }
270  memcpy(buffer,tmp_str,cflength);
271  buffer[cflength]=0;
272  yFree( tmp_str );
273  return;
274  }
275  len=strlen(str);
276  if(len>maxlen-1){
277  len=maxlen-1;
278  }
279  memcpy(buffer,str,len);
280  buffer[len]=0;
281  return;
282  }
283  }
284  *buffer=0;
285 }
286 
287 
288 
289 
290 
291 static IOHIDDeviceRef* getDevRef(OSX_HID_REF *hid, CFIndex *deviceCount)
292 {
293 
294  CFSetRef deviceCFSetRef;
295  IOHIDDeviceRef *dev_refs=NULL;
296 
297  *deviceCount = 0;
298 
299  yEnterCriticalSection(&hid->hidMCS);
300  deviceCFSetRef = IOHIDManagerCopyDevices(hid->manager);
301  yLeaveCriticalSection(&hid->hidMCS);
302  if (deviceCFSetRef!= NULL) {
303  // how many devices in the set?
304  *deviceCount = CFSetGetCount( deviceCFSetRef );
305  dev_refs = yMalloc( sizeof(IOHIDDeviceRef) * (u32)*deviceCount );
306  // now extract the device ref's from the set
307  CFSetGetValues( deviceCFSetRef, (const void **) dev_refs );
308  }
309  return dev_refs;
310 }
311 
312 
313 int yyyUSBGetInterfaces(yInterfaceSt **ifaces,int *nbifaceDetect,char *errmsg)
314 {
315  int nbifaceAlloc;
316  int deviceIndex;
317  CFIndex deviceCount;
318  IOHIDDeviceRef *dev_refs;
319 
320  // get all device detected by the OSX
321  dev_refs = getDevRef(&yContext->hid, &deviceCount);
322  if(dev_refs == NULL) {
323  return 0;
324  }
325 
326  // allocate buffer for detected interfaces
327  *nbifaceDetect = 0;
328  nbifaceAlloc = 8;
329  *ifaces =yMalloc(nbifaceAlloc * sizeof(yInterfaceSt));
330  memset(*ifaces, 0 ,nbifaceAlloc * sizeof(yInterfaceSt));
331  for(deviceIndex=0 ; deviceIndex < deviceCount ;deviceIndex++){
332  u16 vendorid;
333  u16 deviceid;
334  IOHIDDeviceRef dev = dev_refs[deviceIndex];
335  yInterfaceSt *iface;
336  vendorid = get_int_property(dev,CFSTR(kIOHIDVendorIDKey));
337  deviceid = get_int_property(dev,CFSTR(kIOHIDProductIDKey));
338  //ensure the buffer of detected interface is big enought
339  if(*nbifaceDetect == nbifaceAlloc){
340  yInterfaceSt *tmp;
341  tmp = (yInterfaceSt*) yMalloc(nbifaceAlloc*2 * sizeof(yInterfaceSt));
342  memset(tmp,0,nbifaceAlloc*2 * sizeof(yInterfaceSt));
343  yMemcpy(tmp,*ifaces, nbifaceAlloc * sizeof(yInterfaceSt) );
344  yFree(*ifaces);
345  *ifaces = tmp;
346  nbifaceAlloc *=2;
347  }
348  iface = *ifaces + *nbifaceDetect;
349  //iface->devref = dev;
350  iface->vendorid = vendorid;
351  iface->deviceid = deviceid;
352  get_txt_property(dev,iface->serial,YOCTO_SERIAL_LEN*2, CFSTR(kIOHIDSerialNumberKey));
353  HALENUMLOG("work on interface %d (%x:%x:%s)\n",deviceIndex,vendorid,deviceid,iface->serial);
354  (*nbifaceDetect)++;
355  }
356  yFree(dev_refs);
357  return YAPI_SUCCESS;
358 }
359 
360 
361 /*****************************************************************
362  * OSX implementation of yyypacket functions
363  *****************************************************************/
364 
365 
366 
367 
368 // return 1 if OS hdl are identicals
369 // 0 if any of the interface has changed
370 int yyyOShdlCompare( yPrivDeviceSt *dev, yInterfaceSt *newdev)
371 {
372  if(dev->infos.nbinbterfaces != 1){
373  HALLOG("bad number of inteface for %s (%d)\n",dev->infos.serial,dev->infos.nbinbterfaces);
374  return 0;
375  }
376  return 1;
377 }
378 
379 
380 
381 
382 static void Handle_IOHIDDeviceIOHIDReportCallback(
383  void * inContext, // context from IOHIDDeviceRegisterInputReportCallback
384  IOReturn inResult, // completion result for the input report operation
385  void * inSender, // IOHIDDeviceRef of the device this report is from
386  IOHIDReportType inType, // the report type
387  uint32_t inReportID, // the report ID
388  uint8_t * inReport, // pointer to the report data
389  CFIndex InReportLength) // the actual size of the input report
390 {
391  yInterfaceSt *iface= (yInterfaceSt*) inContext;
392  yPktQueuePushD2H(iface,&iface->tmprxpkt,NULL);
393  memset(&iface->tmprxpkt,0xff,sizeof(USB_Packet));
394 }
395 
396 
397 int yyySetup(yInterfaceSt *iface,char *errmsg)
398 {
399  char str[32];
400  int i;
401  CFIndex deviceCount;
402  IOHIDDeviceRef *dev_refs;
403 
404 
405  if (yContext->osx_flags & YCTX_OSX_MULTIPLES_HID) {
406  if (YISERR(setupHIDManager(yContext, &iface->hid,errmsg))) {
407  return YAPI_IO_ERROR;
408  }
409  // get all device detected by the OSX
410  dev_refs = getDevRef(&iface->hid, &deviceCount);
411  } else {
412  dev_refs = getDevRef(&yContext->hid, &deviceCount);
413  }
414  if(dev_refs == NULL) {
415  return YERRMSG(YAPI_IO_ERROR,"Device disapear before yyySetup");
416  }
417 
418 
419  for(i=0 ; i < deviceCount ;i++){
420  u16 vendorid;
421  u16 deviceid;
422  IOHIDDeviceRef dev = dev_refs[i];
423  vendorid = get_int_property(dev,CFSTR(kIOHIDVendorIDKey));
424  deviceid = get_int_property(dev,CFSTR(kIOHIDProductIDKey));
425  if (iface->vendorid == vendorid && iface->deviceid == deviceid){
426  char serial[YOCTO_SERIAL_LEN * 2];
427  memset(serial, 0, YOCTO_SERIAL_LEN * 2);
428  get_txt_property(dev,serial,YOCTO_SERIAL_LEN * 2, CFSTR(kIOHIDSerialNumberKey));
429  if (YSTRCMP(serial, iface->serial) == 0){
430  HALLOG("right Interface detected (%x:%x:%s)\n",vendorid,deviceid,iface->serial);
431  iface->devref = dev;
432  break;
433  }
434  }
435  }
436  yFree(dev_refs);
437  if (i == deviceCount) {
438  return YERRMSG(YAPI_IO_ERROR,"Unable to match device detected");
439  }
440 
441  IOReturn ret = IOHIDDeviceOpen(iface->devref, kIOHIDOptionsTypeNone);
442  if (ret != kIOReturnSuccess) {
443  YSPRINTF(str,32,"Unable to open device (0x%x)",ret);
444  return YERRMSG(YAPI_IO_ERROR,str);
445  }
446 
447  yPktQueueInit(&iface->rxQueue);
448  yPktQueueInit(&iface->txQueue);
449 
450 
451  /* Create the Run Loop Mode for this device. printing the reference seems to work. */
452  sprintf(str, "yocto_%p", iface->devref);
453  iface->run_loop_mode = CFStringCreateWithCString(NULL, str, kCFStringEncodingASCII);
454  /* Attach the device to a Run Loop */
455  IOHIDDeviceScheduleWithRunLoop(iface->devref, yContext->usb_run_loop, iface->run_loop_mode);
456  IOHIDDeviceRegisterInputReportCallback( iface->devref, // IOHIDDeviceRef for the HID device
457  (u8*) &iface->tmprxpkt, // pointer to the report data
458  USB_PKT_SIZE, // number of bytes in the report (CFIndex)
459  &Handle_IOHIDDeviceIOHIDReportCallback, // the callback routine
460  iface); // context passed to callback
461 
462  // save setuped iface pointer in context in order
463  // to retreive it durring unplugcallback
464  for (i=0; i< SETUPED_IFACE_CACHE_SIZE ; i++) {
465  if(yContext->setupedIfaceCache[i]==NULL){
466  yContext->setupedIfaceCache[i] = iface;
467  break;
468  }
469  }
470  if (i==SETUPED_IFACE_CACHE_SIZE) {
471  return YERRMSG(YAPI_IO_ERROR,"Too many setuped USB interfaces");
472  }
473  iface->flags.yyySetupDone = 1;
474  return 0;
475 }
476 
477 
478 
479 int yyySignalOutPkt(yInterfaceSt *iface, char *errmsg)
480 {
481  int res =YAPI_SUCCESS;
482  pktItem *pktitem;
483 
484  yPktQueuePopH2D(iface, &pktitem);
485  while (pktitem!=NULL){
486  if(iface->devref==NULL){
487  yFree(pktitem);
488  return YERR(YAPI_IO_ERROR);
489  }
490  res = IOHIDDeviceSetReport(iface->devref,
491  kIOHIDReportTypeOutput,
492  0, /* Report ID*/
493  (u8*)&pktitem->pkt, sizeof(USB_Packet));
494  yFree(pktitem);
495  if (res != kIOReturnSuccess) {
496  dbglog("IOHIDDeviceSetReport failed with 0x%x\n", res);
497  return YERRMSG(YAPI_IO_ERROR,"IOHIDDeviceSetReport failed");;
498  }
499  yPktQueuePopH2D(iface, &pktitem);
500  }
501  return YAPI_SUCCESS;
502 }
503 
504 
505 
506 void yyyPacketShutdown(yInterfaceSt *iface)
507 {
508  int i;
509 
510  // remove iface from setuped ifaces
511  for (i=0; i< SETUPED_IFACE_CACHE_SIZE ; i++) {
512  if(yContext->setupedIfaceCache[i]==iface){
513  yContext->setupedIfaceCache[i] = NULL;
514  break;
515  }
516  }
517  YASSERT(i<SETUPED_IFACE_CACHE_SIZE);
518  if(iface->devref!=NULL){
519  IOHIDDeviceRegisterInputReportCallback(iface->devref, // IOHIDDeviceRef for the HID device
520  (u8*) &iface->tmprxpkt, // pointer to the report data (uint8_t's)
521  USB_PKT_SIZE, // number of bytes in the report (CFIndex)
522  NULL, // the callback routine
523  iface); // context passed to callback
524  IOHIDDeviceClose(iface->devref, kIOHIDOptionsTypeNone);
525  iface->devref=NULL;
526  }
527  yPktQueueFree(&iface->rxQueue);
528  yPktQueueFree(&iface->txQueue);
529  iface->flags.yyySetupDone = 0;
530  CFRelease(iface->run_loop_mode);
531  if (yContext->osx_flags & YCTX_OSX_MULTIPLES_HID) {
532  stopHIDManager(&iface->hid);
533  }
534 }
535 
536 #endif
537 
538 #ifdef IOS_API
539 #include "yproto.h"
540 
541 int yyyUSB_init(yContextSt *ctx,char *errmsg)
542 {
543  return YAPI_SUCCESS;
544 }
545 
546 int yyyUSB_stop(yContextSt *ctx,char *errmsg)
547 {
548  return 0;
549 }
550 
551 int yyyUSBGetInterfaces(yInterfaceSt **ifaces,int *nbifaceDetect,char *errmsg)
552 {
553  *nbifaceDetect = 0;
554  return 0;
555 }
556 
557 int yyyOShdlCompare( yPrivDeviceSt *dev, yInterfaceSt *newdev)
558 {
559  return 1;
560 }
561 
562 int yyySetup(yInterfaceSt *iface,char *errmsg)
563 {
564  return YERR(YAPI_NOT_SUPPORTED);
565 }
566 
567 int yyySignalOutPkt(yInterfaceSt *iface, char *errmsg)
568 {
569  return -1;
570 }
571 
572 void yyyPacketShutdown(yInterfaceSt *iface)
573 {}
574 
575 #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
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 SETUPED_IFACE_CACHE_SIZE
Definition: yproto.h:890
#define HALENUMLOG(fmt, args...)
Definition: yproto.h:310
int yyySignalOutPkt(yInterfaceSt *iface, char *errmsg)
#define USB_PKT_SIZE
Definition: ydef.h:467
pktQueue txQueue
Definition: yproto.h:572
int yyyUSB_stop(yContextSt *ctx, char *errmsg)
pktQueue rxQueue
Definition: yproto.h:571
#define YASSERT(x)
Definition: yproto.h:454
#define YSPRINTF
Definition: yproto.h:238
#define YOCTO_VENDORID
Definition: ydef.h:402
#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
yInterfaceSt * setupedIfaceCache[SETUPED_IFACE_CACHE_SIZE]
Definition: yproto.h:962
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
void yyyPacketShutdown(yInterfaceSt *iface)
struct _yInterfaceSt::@69 flags
#define YCTX_OSX_MULTIPLES_HID
Definition: yproto.h:920
char serial[YOCTO_SERIAL_LEN]
Definition: ydef.h:454
u16 nbinbterfaces
Definition: ydef.h:451
#define yMemcpy(dst, src, size)
Definition: yproto.h:204
int yyyOShdlCompare(yPrivDeviceSt *dev, yInterfaceSt *newiface)
#define YISERR(retcode)
Definition: ydef.h:394
u32 yyySetupDone
Definition: yproto.h:569
#define YSTRCMP(A, B)
Definition: yproto.h:226
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