hidapi.cpp
Go to the documentation of this file.
1 /* This file is adapted version of the hidapi.c file from http://github.com/signal11/hidapi,
2  modified for a cxx compiler. It only compiles for the MacOS platform */
3 
4 #include <IOKit/hid/IOHIDManager.h>
5 #include <IOKit/hid/IOHIDKeys.h>
6 #include <IOKit/IOKitLib.h>
7 #include <CoreFoundation/CoreFoundation.h>
8 #include <wchar.h>
9 #include <locale.h>
10 #include <pthread.h>
11 #include <sys/time.h>
12 #include <unistd.h>
13 #include <dlfcn.h>
14 
15 #include "hidapi.h"
16 
17 /* Barrier implementation because Mac OSX doesn't have pthread_barrier.
18  It also doesn't have clock_gettime(). So much for POSIX and SUSv2.
19  This implementation came from Brent Priddy and was posted on
20  StackOverflow. It is used with his permission. */
22 typedef struct pthread_barrier {
23  pthread_mutex_t mutex;
24  pthread_cond_t cond;
25  int count;
28 
29 static int pthread_barrier_init(pthread_barrier_t *barrier, const pthread_barrierattr_t *attr, unsigned int count)
30 {
31  if(count == 0) {
32  errno = EINVAL;
33  return -1;
34  }
35 
36  if(pthread_mutex_init(&barrier->mutex, 0) < 0) {
37  return -1;
38  }
39  if(pthread_cond_init(&barrier->cond, 0) < 0) {
40  pthread_mutex_destroy(&barrier->mutex);
41  return -1;
42  }
43  barrier->trip_count = count;
44  barrier->count = 0;
45 
46  return 0;
47 }
48 
50 {
51  pthread_cond_destroy(&barrier->cond);
52  pthread_mutex_destroy(&barrier->mutex);
53  return 0;
54 }
55 
57 {
58  pthread_mutex_lock(&barrier->mutex);
59  ++(barrier->count);
60  if(barrier->count >= barrier->trip_count)
61  {
62  barrier->count = 0;
63  pthread_cond_broadcast(&barrier->cond);
64  pthread_mutex_unlock(&barrier->mutex);
65  return 1;
66  }
67  else
68  {
69  pthread_cond_wait(&barrier->cond, &(barrier->mutex));
70  pthread_mutex_unlock(&barrier->mutex);
71  return 0;
72  }
73 }
74 
75 static int return_data(hidapi_device *dev, unsigned char *data, size_t length);
76 
77 /* Linked List of input reports received from the device. */
78 struct input_report {
80  size_t len;
81  struct input_report *next;
82 };
83 
84 struct hid_device_ {
85  IOHIDDeviceRef device_handle;
86  int blocking;
89  CFStringRef run_loop_mode;
90  CFRunLoopRef run_loop;
91  CFRunLoopSourceRef source;
95 
96  pthread_t thread;
97  pthread_mutex_t mutex; /* Protects input_reports */
98  pthread_cond_t condition;
99  pthread_barrier_t barrier; /* Ensures correct startup sequence */
100  pthread_barrier_t shutdown_barrier; /* Ensures correct shutdown sequence */
102 };
103 
105 {
106  hidapi_device *dev = (hidapi_device *)calloc(1, sizeof(hidapi_device));
107  dev->device_handle = NULL;
108  dev->blocking = 1;
109  dev->uses_numbered_reports = 0;
110  dev->disconnected = 0;
111  dev->run_loop_mode = NULL;
112  dev->run_loop = NULL;
113  dev->source = NULL;
114  dev->input_report_buf = NULL;
115  dev->input_reports = NULL;
116  dev->shutdown_thread = 0;
117 
118  /* Thread objects */
119  pthread_mutex_init(&dev->mutex, NULL);
120  pthread_cond_init(&dev->condition, NULL);
121  pthread_barrier_init(&dev->barrier, NULL, 2);
123 
124  return dev;
125 }
126 
128 {
129  if (!dev)
130  return;
131 
132  /* Delete any input reports still left over. */
133  struct input_report *rpt = dev->input_reports;
134  while (rpt) {
135  struct input_report *next = rpt->next;
136  free(rpt->data);
137  free(rpt);
138  rpt = next;
139  }
140 
141  /* Free the string and the report buffer. The check for NULL
142  is necessary here as CFRelease() doesn't handle NULL like
143  free() and others do. */
144  if (dev->run_loop_mode)
145  CFRelease(dev->run_loop_mode);
146  if (dev->source)
147  CFRelease(dev->source);
148  free(dev->input_report_buf);
149 
150  /* Clean up the thread objects */
153  pthread_cond_destroy(&dev->condition);
154  pthread_mutex_destroy(&dev->mutex);
155 
156  /* Free the structure itself. */
157  free(dev);
158 }
159 
160 static IOHIDManagerRef hid_mgr = 0x0;
161 
162 
163 #if 0
164 static void register_error(hid_device *device, const char *op)
165 {
166 
167 }
168 #endif
169 
170 
171 static int32_t get_int_property(IOHIDDeviceRef device, CFStringRef key)
172 {
173  CFTypeRef ref;
174  int32_t value;
175 
176  ref = IOHIDDeviceGetProperty(device, key);
177  if (ref) {
178  if (CFGetTypeID(ref) == CFNumberGetTypeID()) {
179  CFNumberGetValue((CFNumberRef) ref, kCFNumberSInt32Type, &value);
180  return value;
181  }
182  }
183  return 0;
184 }
185 
186 static unsigned short get_vendor_id(IOHIDDeviceRef device)
187 {
188  return get_int_property(device, CFSTR(kIOHIDVendorIDKey));
189 }
190 
191 static unsigned short get_product_id(IOHIDDeviceRef device)
192 {
193  return get_int_property(device, CFSTR(kIOHIDProductIDKey));
194 }
195 
196 static int32_t get_max_report_length(IOHIDDeviceRef device)
197 {
198  return get_int_property(device, CFSTR(kIOHIDMaxInputReportSizeKey));
199 }
200 
201 static int get_string_property(IOHIDDeviceRef device, CFStringRef prop, wchar_t *buf, size_t len)
202 {
203  CFStringRef str;
204 
205  if (!len)
206  return 0;
207 
208  str = (CFStringRef) IOHIDDeviceGetProperty(device, prop);
209 
210  buf[0] = 0;
211 
212  if (str) {
213  CFIndex str_len = CFStringGetLength(str);
214  CFRange range;
215  CFIndex used_buf_len;
216  CFIndex chars_copied;
217 
218  len --;
219 
220  range.location = 0;
221  range.length = ((size_t)str_len > len)? len: (size_t)str_len;
222  chars_copied = CFStringGetBytes(str,
223  range,
224  kCFStringEncodingUTF32LE,
225  (char)'?',
226  FALSE,
227  (UInt8*)buf,
228  len * sizeof(wchar_t),
229  &used_buf_len);
230 
231  if (chars_copied == len)
232  buf[len] = 0; /* len is decremented above */
233  else
234  buf[chars_copied] = 0;
235 
236  return 0;
237  }
238  else
239  return -1;
240 
241 }
242 
243 static int get_serial_number(IOHIDDeviceRef device, wchar_t *buf, size_t len)
244 {
245  return get_string_property(device, CFSTR(kIOHIDSerialNumberKey), buf, len);
246 }
247 
248 static int get_manufacturer_string(IOHIDDeviceRef device, wchar_t *buf, size_t len)
249 {
250  return get_string_property(device, CFSTR(kIOHIDManufacturerKey), buf, len);
251 }
252 
253 static int get_product_string(IOHIDDeviceRef device, wchar_t *buf, size_t len)
254 {
255  return get_string_property(device, CFSTR(kIOHIDProductKey), buf, len);
256 }
257 
258 
259 /* Implementation of wcsdup() for Mac. */
260 static wchar_t *dup_wcs(const wchar_t *s)
261 {
262  size_t len = wcslen(s);
263  wchar_t *ret = (wchar_t *)malloc((len+1)*sizeof(wchar_t));
264  wcscpy(ret, s);
265 
266  return ret;
267 }
268 
269 /* hidapi_IOHIDDeviceGetService()
270  *
271  * Return the io_service_t corresponding to a given IOHIDDeviceRef, either by:
272  * - on OS X 10.6 and above, calling IOHIDDeviceGetService()
273  * - on OS X 10.5, extract it from the IOHIDDevice struct
274  */
275 static io_service_t hidapi_IOHIDDeviceGetService(IOHIDDeviceRef device)
276 {
277  static void *iokit_framework = NULL;
278  static io_service_t (*dynamic_IOHIDDeviceGetService)(IOHIDDeviceRef) = NULL;
279 
280  /* Use dlopen()/dlsym() to get a pointer to IOHIDDeviceGetService() if it exists.
281  * If any of these steps fail, dynamic_IOHIDDeviceGetService will be left NULL
282  * and the fallback method will be used.
283  */
284  if (iokit_framework == NULL) {
285  iokit_framework = dlopen("/System/Library/IOKit.framework/IOKit", RTLD_LAZY);
286 
287  if (iokit_framework != NULL)
288  dynamic_IOHIDDeviceGetService = (io_service_t (*)(IOHIDDeviceRef))dlsym(iokit_framework, "IOHIDDeviceGetService");
289  }
290 
291  if (dynamic_IOHIDDeviceGetService != NULL) {
292  /* Running on OS X 10.6 and above: IOHIDDeviceGetService() exists */
293  return dynamic_IOHIDDeviceGetService(device);
294  }
295  else
296  {
297  /* Running on OS X 10.5: IOHIDDeviceGetService() doesn't exist.
298  *
299  * Be naughty and pull the service out of the IOHIDDevice.
300  * IOHIDDevice is an opaque struct not exposed to applications, but its
301  * layout is stable through all available versions of OS X.
302  * Tested and working on OS X 10.5.8 i386, x86_64, and ppc.
303  */
304  struct IOHIDDevice_internal {
305  /* The first field of the IOHIDDevice struct is a
306  * CFRuntimeBase (which is a private CF struct).
307  *
308  * a, b, and c are the 3 fields that make up a CFRuntimeBase.
309  * See http://opensource.apple.com/source/CF/CF-476.18/CFRuntime.h
310  *
311  * The second field of the IOHIDDevice is the io_service_t we're looking for.
312  */
313  uintptr_t a;
314  uint8_t b[4];
315 #if __LP64__
316  uint32_t c;
317 #endif
318  io_service_t service;
319  };
320  struct IOHIDDevice_internal *tmp = (struct IOHIDDevice_internal *)device;
321 
322  return tmp->service;
323  }
324 }
325 
326 /* Initialize the IOHIDManager. Return 0 for success and -1 for failure. */
327 static int init_hid_manager(void)
328 {
329  /* Initialize all the HID Manager Objects */
330  hid_mgr = IOHIDManagerCreate(kCFAllocatorDefault, kIOHIDOptionsTypeNone);
331  if (hid_mgr) {
332  IOHIDManagerSetDeviceMatching(hid_mgr, NULL);
333  IOHIDManagerScheduleWithRunLoop(hid_mgr, CFRunLoopGetCurrent(), kCFRunLoopDefaultMode);
334  return 0;
335  }
336 
337  return -1;
338 }
339 
340 /* Initialize the IOHIDManager if necessary. This is the public function, and
341  it is safe to call this function repeatedly. Return 0 for success and -1
342  for failure. */
344 {
345  if (!hid_mgr) {
346  return init_hid_manager();
347  }
348 
349  /* Already initialized. */
350  return 0;
351 }
352 
354 {
355  if (hid_mgr) {
356  /* Close the HID manager. */
357  IOHIDManagerClose(hid_mgr, kIOHIDOptionsTypeNone);
358  CFRelease(hid_mgr);
359  hid_mgr = NULL;
360  }
361 
362  return 0;
363 }
364 
365 static void process_pending_events(void) {
366  SInt32 res;
367  do {
368  res = CFRunLoopRunInMode(kCFRunLoopDefaultMode, 0.001, FALSE);
369  } while(res != kCFRunLoopRunFinished && res != kCFRunLoopRunTimedOut);
370 }
371 
372 struct hidapi_device_info HID_API_EXPORT *hid_enumerate(unsigned short vendor_id, unsigned short product_id)
373 {
374  struct hidapi_device_info *root = NULL; /* return object */
375  struct hidapi_device_info *cur_dev = NULL;
376  CFIndex num_devices;
377  int i;
378 
379  /* Set up the HID Manager if it hasn't been done */
380  if (hid_init() < 0)
381  return NULL;
382 
383  /* give the IOHIDManager a chance to update itself */
385 
386  /* Get a list of the Devices */
387  IOHIDManagerSetDeviceMatching(hid_mgr, NULL);
388  CFSetRef device_set = IOHIDManagerCopyDevices(hid_mgr);
389 
390  /* Convert the list into a C array so we can iterate easily. */
391  num_devices = CFSetGetCount(device_set);
392  IOHIDDeviceRef *device_array = reinterpret_cast<IOHIDDeviceRef *>(calloc(num_devices, sizeof(IOHIDDeviceRef)));
393  CFSetGetValues(device_set, (const void **) device_array);
394 
395  /* Iterate over each device, making an entry for it. */
396  for (i = 0; i < num_devices; i++) {
397  unsigned short dev_vid;
398  unsigned short dev_pid;
399 #define BUF_LEN 256
400  wchar_t buf[BUF_LEN];
401 
402  IOHIDDeviceRef dev = device_array[i];
403 
404  if (!dev) {
405  continue;
406  }
407  dev_vid = get_vendor_id(dev);
408  dev_pid = get_product_id(dev);
409 
410  /* Check the VID/PID against the arguments */
411  if ((vendor_id == 0x0 || vendor_id == dev_vid) &&
412  (product_id == 0x0 || product_id == dev_pid)) {
413  struct hidapi_device_info *tmp;
414  io_object_t iokit_dev;
415  kern_return_t res;
416  io_string_t path;
417 
418  /* VID/PID match. Create the record. */
419  tmp = reinterpret_cast<hidapi_device_info *> (malloc(sizeof(struct hidapi_device_info)));
420  if (cur_dev) {
421  cur_dev->next = tmp;
422  }
423  else {
424  root = tmp;
425  }
426  cur_dev = tmp;
427 
428  /* Get the Usage Page and Usage for this device. */
429  cur_dev->usage_page = get_int_property(dev, CFSTR(kIOHIDPrimaryUsagePageKey));
430  cur_dev->usage = get_int_property(dev, CFSTR(kIOHIDPrimaryUsageKey));
431 
432  /* Fill out the record */
433  cur_dev->next = NULL;
434 
435  /* Fill in the path (IOService plane) */
436  iokit_dev = hidapi_IOHIDDeviceGetService(dev);
437  res = IORegistryEntryGetPath(iokit_dev, kIOServicePlane, path);
438  if (res == KERN_SUCCESS)
439  cur_dev->path = strdup(path);
440  else
441  cur_dev->path = strdup("");
442 
443  /* Serial Number */
444  get_serial_number(dev, buf, BUF_LEN);
445  cur_dev->serial_number = dup_wcs(buf);
446 
447  /* Manufacturer and Product strings */
448  get_manufacturer_string(dev, buf, BUF_LEN);
449  cur_dev->manufacturer_string = dup_wcs(buf);
450  get_product_string(dev, buf, BUF_LEN);
451  cur_dev->product_string = dup_wcs(buf);
452 
453  /* VID/PID */
454  cur_dev->vendor_id = dev_vid;
455  cur_dev->product_id = dev_pid;
456 
457  /* Release Number */
458  cur_dev->release_number = get_int_property(dev, CFSTR(kIOHIDVersionNumberKey));
459 
460  /* Interface Number (Unsupported on Mac)*/
461  cur_dev->interface_number = -1;
462  }
463  }
464 
465  free(device_array);
466  CFRelease(device_set);
467 
468  return root;
469 }
470 
472 {
473  /* This function is identical to the Linux version. Platform independent. */
474  struct hidapi_device_info *d = devs;
475  while (d) {
476  struct hidapi_device_info *next = d->next;
477  free(d->path);
478  free(d->serial_number);
479  free(d->manufacturer_string);
480  free(d->product_string);
481  free(d);
482  d = next;
483  }
484 }
485 
486 hidapi_device * HID_API_EXPORT hid_open(unsigned short vendor_id, unsigned short product_id, const wchar_t *serial_number)
487 {
488  /* This function is identical to the Linux version. Platform independent. */
489  struct hidapi_device_info *devs, *cur_dev;
490  const char *path_to_open = NULL;
492 
493  devs = hid_enumerate(vendor_id, product_id);
494  cur_dev = devs;
495  while (cur_dev) {
496  if (cur_dev->vendor_id == vendor_id &&
497  cur_dev->product_id == product_id) {
498  if (serial_number) {
499  if (wcscmp(serial_number, cur_dev->serial_number) == 0) {
500  path_to_open = cur_dev->path;
501  break;
502  }
503  }
504  else {
505  path_to_open = cur_dev->path;
506  break;
507  }
508  }
509  cur_dev = cur_dev->next;
510  }
511 
512  if (path_to_open) {
513  /* Open the device */
514  handle = hid_open_path(path_to_open);
515  }
516 
517  hid_free_enumeration(devs);
518 
519  return handle;
520 }
521 
522 static void hid_device_removal_callback(void *context, IOReturn result,
523  void *sender)
524 {
525  /* Stop the Run Loop for this device. */
526  hidapi_device *d = reinterpret_cast<hidapi_device*>(context);
527 
528  d->disconnected = 1;
529  CFRunLoopStop(d->run_loop);
530 }
531 
532 /* The Run Loop calls this function for each input report received.
533  This function puts the data into a linked list to be picked up by
534  hid_read(). */
535 static void hid_report_callback(void *context, IOReturn result, void *sender,
536  IOHIDReportType report_type, uint32_t report_id,
537  uint8_t *report, CFIndex report_length)
538 {
539  struct input_report *rpt;
540  hidapi_device *dev = reinterpret_cast<hidapi_device*>(context);
541 
542  /* Make a new Input Report object */
543  rpt = reinterpret_cast<input_report*>(calloc(1, sizeof(struct input_report)));
544  rpt->data = reinterpret_cast<uint8_t*> (calloc(1, report_length));
545  memcpy(rpt->data, report, report_length);
546  rpt->len = report_length;
547  rpt->next = NULL;
548 
549  /* Lock this section */
550  pthread_mutex_lock(&dev->mutex);
551 
552  /* Attach the new report object to the end of the list. */
553  if (dev->input_reports == NULL) {
554  /* The list is empty. Put it at the root. */
555  dev->input_reports = rpt;
556  }
557  else {
558  /* Find the end of the list and attach. */
559  struct input_report *cur = dev->input_reports;
560  int num_queued = 0;
561  while (cur->next != NULL) {
562  cur = cur->next;
563  num_queued++;
564  }
565  cur->next = rpt;
566 
567  /* Pop one off if we've reached 30 in the queue. This
568  way we don't grow forever if the user never reads
569  anything from the device. */
570  if (num_queued > 30) {
571  return_data(dev, NULL, 0);
572  }
573  }
574 
575  /* Signal a waiting thread that there is data. */
576  pthread_cond_signal(&dev->condition);
577 
578  /* Unlock */
579  pthread_mutex_unlock(&dev->mutex);
580 
581 }
582 
583 /* This gets called when the read_thread's run loop gets signaled by
584  hid_close(), and serves to stop the read_thread's run loop. */
585 static void perform_signal_callback(void *context)
586 {
587  hidapi_device *dev = reinterpret_cast<hidapi_device*>(context);
588  CFRunLoopStop(dev->run_loop); /*TODO: CFRunLoopGetCurrent()*/
589 }
590 
591 static void *read_thread(void *param)
592 {
593  hidapi_device *dev = reinterpret_cast<hidapi_device*>(param);
594  SInt32 code;
595 
596  /* Move the device's run loop to this thread. */
597  IOHIDDeviceScheduleWithRunLoop(dev->device_handle, CFRunLoopGetCurrent(), dev->run_loop_mode);
598 
599  /* Create the RunLoopSource which is used to signal the
600  event loop to stop when hid_close() is called. */
601  CFRunLoopSourceContext ctx;
602  memset(&ctx, 0, sizeof(ctx));
603  ctx.version = 0;
604  ctx.info = dev;
605  ctx.perform = &perform_signal_callback;
606  dev->source = CFRunLoopSourceCreate(kCFAllocatorDefault, 0/*order*/, &ctx);
607  CFRunLoopAddSource(CFRunLoopGetCurrent(), dev->source, dev->run_loop_mode);
608 
609  /* Store off the Run Loop so it can be stopped from hid_close()
610  and on device disconnection. */
611  dev->run_loop = CFRunLoopGetCurrent();
612 
613  /* Notify the main thread that the read thread is up and running. */
615 
616  /* Run the Event Loop. CFRunLoopRunInMode() will dispatch HID input
617  reports into the hid_report_callback(). */
618  while (!dev->shutdown_thread && !dev->disconnected) {
619  code = CFRunLoopRunInMode(dev->run_loop_mode, 1000/*sec*/, FALSE);
620  /* Return if the device has been disconnected */
621  if (code == kCFRunLoopRunFinished) {
622  dev->disconnected = 1;
623  break;
624  }
625 
626 
627  /* Break if The Run Loop returns Finished or Stopped. */
628  if (code != kCFRunLoopRunTimedOut &&
629  code != kCFRunLoopRunHandledSource) {
630  /* There was some kind of error. Setting
631  shutdown seems to make sense, but
632  there may be something else more appropriate */
633  dev->shutdown_thread = 1;
634  break;
635  }
636  }
637 
638  /* Now that the read thread is stopping, Wake any threads which are
639  waiting on data (in hid_read_timeout()). Do this under a mutex to
640  make sure that a thread which is about to go to sleep waiting on
641  the condition actually will go to sleep before the condition is
642  signaled. */
643  pthread_mutex_lock(&dev->mutex);
644  pthread_cond_broadcast(&dev->condition);
645  pthread_mutex_unlock(&dev->mutex);
646 
647  /* Wait here until hid_close() is called and makes it past
648  the call to CFRunLoopWakeUp(). This thread still needs to
649  be valid when that function is called on the other thread. */
651 
652  return NULL;
653 }
654 
655 /* hid_open_path()
656  *
657  * path must be a valid path to an IOHIDDevice in the IOService plane
658  * Example: "IOService:/AppleACPIPlatformExpert/PCI0@0/AppleACPIPCI/EHC1@1D,7/AppleUSBEHCI/PLAYSTATION(R)3 Controller@fd120000/IOUSBInterface@0/IOUSBHIDDriver"
659  */
661 {
662  hidapi_device *dev = NULL;
663  io_registry_entry_t entry = MACH_PORT_NULL;
664 
665  dev = new_hid_device();
666 
667  /* Set up the HID Manager if it hasn't been done */
668  if (hid_init() < 0)
669  return NULL;
670 
671  bool return_error = false;
672 
673  /* Get the IORegistry entry for the given path */
674  entry = IORegistryEntryFromPath(kIOMasterPortDefault, path);
675  if (entry == MACH_PORT_NULL) {
676  /* Path wasn't valid (maybe device was removed?) */
677  return_error = true;
678  }
679 
680  /* Create an IOHIDDevice for the entry */
681  dev->device_handle = IOHIDDeviceCreate(kCFAllocatorDefault, entry);
682  if (dev->device_handle == NULL) {
683  /* Error creating the HID device */
684  return_error = true;
685  }
686 
687  /* Open the IOHIDDevice */
688  IOReturn ret = IOHIDDeviceOpen(dev->device_handle, kIOHIDOptionsTypeSeizeDevice);
689  if (ret == kIOReturnSuccess) {
690  char str[32];
691 
692  /* Create the buffers for receiving data */
694  dev->input_report_buf = reinterpret_cast<uint8_t*>(calloc(dev->max_input_report_len, sizeof(uint8_t)));
695 
696  /* Create the Run Loop Mode for this device.
697  printing the reference seems to work. */
698  sprintf(str, "HIDAPI_%p", dev->device_handle);
699  dev->run_loop_mode =
700  CFStringCreateWithCString(NULL, str, kCFStringEncodingASCII);
701 
702  /* Attach the device to a Run Loop */
703  IOHIDDeviceRegisterInputReportCallback(
705  &hid_report_callback, dev);
706  IOHIDDeviceRegisterRemovalCallback(dev->device_handle, hid_device_removal_callback, dev);
707 
708  /* Start the read thread */
709  pthread_create(&dev->thread, NULL, read_thread, dev);
710 
711  /* Wait here for the read thread to be initialized. */
713 
714  IOObjectRelease(entry);
715  return dev;
716  }
717  else {
718  return_error = true;;
719  }
720 
721  if (return_error)
722  {
723  if (dev->device_handle != NULL)
724  CFRelease(dev->device_handle);
725 
726  if (entry != MACH_PORT_NULL)
727  IOObjectRelease(entry);
728 
729  free_hid_device(dev);
730  return NULL;
731  }
732 }
733 
734 static int set_report(hidapi_device *dev, IOHIDReportType type, const unsigned char *data, size_t length)
735 {
736  const unsigned char *data_to_send;
737  size_t length_to_send;
738  IOReturn res;
739 
740  /* Return if the device has been disconnected. */
741  if (dev->disconnected)
742  return -1;
743 
744  if (data[0] == 0x0) {
745  /* Not using numbered Reports.
746  Don't send the report number. */
747  data_to_send = data+1;
748  length_to_send = length-1;
749  }
750  else {
751  /* Using numbered Reports.
752  Send the Report Number */
753  data_to_send = data;
754  length_to_send = length;
755  }
756 
757  if (!dev->disconnected) {
758  res = IOHIDDeviceSetReport(dev->device_handle,
759  type,
760  data[0], /* Report ID*/
761  data_to_send, length_to_send);
762 
763  if (res == kIOReturnSuccess) {
764  return length;
765  }
766  else
767  return -1;
768  }
769 
770  return -1;
771 }
772 
773 int HID_API_EXPORT hid_write(hidapi_device *dev, const unsigned char *data, size_t length)
774 {
775  return set_report(dev, kIOHIDReportTypeOutput, data, length);
776 }
777 
778 /* Helper function, so that this isn't duplicated in hid_read(). */
779 static int return_data(hidapi_device *dev, unsigned char *data, size_t length)
780 {
781  /* Copy the data out of the linked list item (rpt) into the
782  return buffer (data), and delete the liked list item. */
783  struct input_report *rpt = dev->input_reports;
784  size_t len = (length < rpt->len)? length: rpt->len;
785  memcpy(data, rpt->data, len);
786  dev->input_reports = rpt->next;
787  free(rpt->data);
788  free(rpt);
789  return len;
790 }
791 
792 static int cond_wait(const hidapi_device *dev, pthread_cond_t *cond, pthread_mutex_t *mutex)
793 {
794  while (!dev->input_reports) {
795  int res = pthread_cond_wait(cond, mutex);
796  if (res != 0)
797  return res;
798 
799  /* A res of 0 means we may have been signaled or it may
800  be a spurious wakeup. Check to see that there's acutally
801  data in the queue before returning, and if not, go back
802  to sleep. See the pthread_cond_timedwait() man page for
803  details. */
804 
805  if (dev->shutdown_thread || dev->disconnected)
806  return -1;
807  }
808 
809  return 0;
810 }
811 
812 static int cond_timedwait(const hidapi_device *dev, pthread_cond_t *cond, pthread_mutex_t *mutex, const struct timespec *abstime)
813 {
814  while (!dev->input_reports) {
815  int res = pthread_cond_timedwait(cond, mutex, abstime);
816  if (res != 0)
817  return res;
818 
819  /* A res of 0 means we may have been signaled or it may
820  be a spurious wakeup. Check to see that there's acutally
821  data in the queue before returning, and if not, go back
822  to sleep. See the pthread_cond_timedwait() man page for
823  details. */
824 
825  if (dev->shutdown_thread || dev->disconnected)
826  return -1;
827  }
828 
829  return 0;
830 
831 }
832 
833 int HID_API_EXPORT hid_read_timeout(hidapi_device *dev, unsigned char *data, size_t length, int milliseconds)
834 {
835  int bytes_read = -1;
836 
837  /* Lock the access to the report list. */
838  pthread_mutex_lock(&dev->mutex);
839 
840  /* There's an input report queued up. Return it. */
841  if (dev->input_reports) {
842  /* Return the first one */
843  bytes_read = return_data(dev, data, length);
844  goto ret;
845  }
846 
847  /* Return if the device has been disconnected. */
848  if (dev->disconnected) {
849  bytes_read = -1;
850  goto ret;
851  }
852 
853  if (dev->shutdown_thread) {
854  /* This means the device has been closed (or there
855  has been an error. An error code of -1 should
856  be returned. */
857  bytes_read = -1;
858  goto ret;
859  }
860 
861  /* There is no data. Go to sleep and wait for data. */
862 
863  if (milliseconds == -1) {
864  /* Blocking */
865  int res;
866  res = cond_wait(dev, &dev->condition, &dev->mutex);
867  if (res == 0)
868  bytes_read = return_data(dev, data, length);
869  else {
870  /* There was an error, or a device disconnection. */
871  bytes_read = -1;
872  }
873  }
874  else if (milliseconds > 0) {
875  /* Non-blocking, but called with timeout. */
876  int res;
877  struct timespec ts;
878  struct timeval tv;
879  gettimeofday(&tv, NULL);
880  TIMEVAL_TO_TIMESPEC(&tv, &ts);
881  ts.tv_sec += milliseconds / 1000;
882  ts.tv_nsec += (milliseconds % 1000) * 1000000;
883  if (ts.tv_nsec >= 1000000000L) {
884  ts.tv_sec++;
885  ts.tv_nsec -= 1000000000L;
886  }
887 
888  res = cond_timedwait(dev, &dev->condition, &dev->mutex, &ts);
889  if (res == 0)
890  bytes_read = return_data(dev, data, length);
891  else if (res == ETIMEDOUT)
892  bytes_read = 0;
893  else
894  bytes_read = -1;
895  }
896  else {
897  /* Purely non-blocking */
898  bytes_read = 0;
899  }
900 
901 ret:
902  /* Unlock */
903  pthread_mutex_unlock(&dev->mutex);
904  return bytes_read;
905 }
906 
907 int HID_API_EXPORT hid_read(hidapi_device *dev, unsigned char *data, size_t length)
908 {
909  return hid_read_timeout(dev, data, length, (dev->blocking)? -1: 0);
910 }
911 
913 {
914  /* All Nonblocking operation is handled by the library. */
915  dev->blocking = !nonblock;
916 
917  return 0;
918 }
919 
920 int HID_API_EXPORT hid_send_feature_report(hidapi_device *dev, const unsigned char *data, size_t length)
921 {
922  return set_report(dev, kIOHIDReportTypeFeature, data, length);
923 }
924 
925 int HID_API_EXPORT hid_get_feature_report(hidapi_device *dev, unsigned char *data, size_t length)
926 {
927  CFIndex len = length;
928  IOReturn res;
929 
930  /* Return if the device has been unplugged. */
931  if (dev->disconnected)
932  return -1;
933 
934  res = IOHIDDeviceGetReport(dev->device_handle,
935  kIOHIDReportTypeFeature,
936  data[0], /* Report ID */
937  data, &len);
938  if (res == kIOReturnSuccess)
939  return len;
940  else
941  return -1;
942 }
943 
944 
946 {
947  if (!dev)
948  return;
949 
950  /* Disconnect the report callback before close. */
951  if (!dev->disconnected) {
952  IOHIDDeviceRegisterInputReportCallback(
954  NULL, dev);
955  IOHIDDeviceRegisterRemovalCallback(dev->device_handle, NULL, dev);
956  IOHIDDeviceUnscheduleFromRunLoop(dev->device_handle, dev->run_loop, dev->run_loop_mode);
957  IOHIDDeviceScheduleWithRunLoop(dev->device_handle, CFRunLoopGetMain(), kCFRunLoopDefaultMode);
958  }
959 
960  /* Cause read_thread() to stop. */
961  dev->shutdown_thread = 1;
962 
963  /* Wake up the run thread's event loop so that the thread can exit. */
964  CFRunLoopSourceSignal(dev->source);
965  CFRunLoopWakeUp(dev->run_loop);
966 
967  /* Notify the read thread that it can shut down now. */
969 
970  /* Wait for read_thread() to end. */
971  pthread_join(dev->thread, NULL);
972 
973  /* Close the OS handle to the device, but only if it's not
974  been unplugged. If it's been unplugged, then calling
975  IOHIDDeviceClose() will crash. */
976  if (!dev->disconnected) {
977  IOHIDDeviceClose(dev->device_handle, kIOHIDOptionsTypeSeizeDevice);
978  }
979 
980  /* Clear out the queue of received reports. */
981  pthread_mutex_lock(&dev->mutex);
982  while (dev->input_reports) {
983  return_data(dev, NULL, 0);
984  }
985  pthread_mutex_unlock(&dev->mutex);
986  CFRelease(dev->device_handle);
987 
988  free_hid_device(dev);
989 }
990 
991 int HID_API_EXPORT_CALL hid_get_manufacturer_string(hidapi_device *dev, wchar_t *string, size_t maxlen)
992 {
993  return get_manufacturer_string(dev->device_handle, string, maxlen);
994 }
995 
996 int HID_API_EXPORT_CALL hid_get_product_string(hidapi_device *dev, wchar_t *string, size_t maxlen)
997 {
998  return get_product_string(dev->device_handle, string, maxlen);
999 }
1000 
1001 int HID_API_EXPORT_CALL hid_get_serial_number_string(hidapi_device *dev, wchar_t *string, size_t maxlen)
1002 {
1003  return get_serial_number(dev->device_handle, string, maxlen);
1004 }
1005 
1006 int HID_API_EXPORT_CALL hid_get_indexed_string(hidapi_device *dev, int string_index, wchar_t *string, size_t maxlen)
1007 {
1008  /* TODO: */
1009 
1010  return 0;
1011 }
1012 
1013 
1015 {
1016  /* TODO: */
1017 
1018  return NULL;
1019 }
1020 
1021 
1022 static int32_t get_location_id(IOHIDDeviceRef device)
1023 {
1024  return get_int_property(device, CFSTR(kIOHIDLocationIDKey));
1025 }
1026 
1027 static int32_t get_usage(IOHIDDeviceRef device)
1028 {
1029  int32_t res;
1030  res = get_int_property(device, CFSTR(kIOHIDDeviceUsageKey));
1031  if (!res)
1032  res = get_int_property(device, CFSTR(kIOHIDPrimaryUsageKey));
1033  return res;
1034 }
1035 
1036 static int32_t get_usage_page(IOHIDDeviceRef device)
1037 {
1038  int32_t res;
1039  res = get_int_property(device, CFSTR(kIOHIDDeviceUsagePageKey));
1040  if (!res)
1041  res = get_int_property(device, CFSTR(kIOHIDPrimaryUsagePageKey));
1042  return res;
1043 }
1044 
1045 static int get_transport(IOHIDDeviceRef device, wchar_t *buf, size_t len)
1046 {
1047  return get_string_property(device, CFSTR(kIOHIDTransportKey), buf, len);
1048 }
int pthread_barrierattr_t
Definition: hidapi.cpp:21
pthread_mutex_t mutex
Definition: hidapi.cpp:23
unsigned short usage
Definition: hidapi.h:70
void HID_API_EXPORT hid_free_enumeration(struct hidapi_device_info *devs)
Free an enumeration Linked List.
Definition: hidapi.cpp:471
GLboolean GLboolean GLboolean b
static int32_t get_usage_page(IOHIDDeviceRef device)
Definition: hidapi.cpp:1036
static IOHIDManagerRef hid_mgr
Definition: hidapi.cpp:160
uint8_t * data
Definition: hidapi.cpp:79
static unsigned short get_product_id(IOHIDDeviceRef device)
Definition: hidapi.cpp:191
struct hidapi_device_info * next
Definition: hidapi.h:78
int HID_API_EXPORT_CALL hid_get_serial_number_string(hidapi_device *dev, wchar_t *string, size_t maxlen)
Get The Serial Number String from a HID device.
Definition: hidapi.cpp:1001
CFRunLoopRef run_loop
Definition: hidapi.cpp:90
GLdouble s
CFRunLoopSourceRef source
Definition: hidapi.cpp:91
int HID_API_EXPORT hid_write(hidapi_device *dev, const unsigned char *data, size_t length)
Write an Output report to a HID device.
Definition: hidapi.cpp:773
static int get_transport(IOHIDDeviceRef device, wchar_t *buf, size_t len)
Definition: hidapi.cpp:1045
#define HID_API_EXPORT
Definition: hidapi.h:36
static int32_t get_usage(IOHIDDeviceRef device)
Definition: hidapi.cpp:1027
GLuint64 GLenum void * handle
Definition: glext.h:7785
pthread_mutex_t mutex
Definition: hidapi.cpp:97
GLsizei const GLchar *const * path
Definition: glext.h:4276
GLfloat value
int disconnected
Definition: hidapi.cpp:88
static int return_data(hidapi_device *dev, unsigned char *data, size_t length)
Definition: hidapi.cpp:779
static int get_serial_number(IOHIDDeviceRef device, wchar_t *buf, size_t len)
Definition: hidapi.cpp:243
static int32_t get_max_report_length(IOHIDDeviceRef device)
Definition: hidapi.cpp:196
static unsigned short get_vendor_id(IOHIDDeviceRef device)
Definition: hidapi.cpp:186
int HID_API_EXPORT hid_read_timeout(hidapi_device *dev, unsigned char *data, size_t length, int milliseconds)
Read an Input report from a HID device with timeout.
Definition: hidapi.cpp:833
pthread_cond_t cond
Definition: hidapi.cpp:24
struct input_report * input_reports
Definition: hidapi.cpp:94
void HID_API_EXPORT hid_close(hidapi_device *dev)
Close a HID device.
Definition: hidapi.cpp:945
d
Definition: rmse.py:171
IOHIDDeviceRef device_handle
Definition: hidapi.cpp:85
GLuint entry
Definition: glext.h:10991
unsigned short product_id
Definition: hidapi.h:55
unsigned char uint8_t
Definition: stdint.h:78
pthread_cond_t condition
Definition: hidapi.cpp:98
int shutdown_thread
Definition: hidapi.cpp:101
static wchar_t * dup_wcs(const wchar_t *s)
Definition: hidapi.cpp:260
wchar_t * serial_number
Definition: hidapi.h:57
static int pthread_barrier_init(pthread_barrier_t *barrier, const pthread_barrierattr_t *attr, unsigned int count)
Definition: hidapi.cpp:29
int HID_API_EXPORT_CALL hid_get_manufacturer_string(hidapi_device *dev, wchar_t *string, size_t maxlen)
Get The Manufacturer String from a HID device.
Definition: hidapi.cpp:991
pthread_barrier_t shutdown_barrier
Definition: hidapi.cpp:100
CFIndex max_input_report_len
Definition: hidapi.cpp:93
static int get_string_property(IOHIDDeviceRef device, CFStringRef prop, wchar_t *buf, size_t len)
Definition: hidapi.cpp:201
GLboolean GLboolean GLboolean GLboolean a
GLenum GLuint GLenum GLsizei const GLchar * buf
GLenum GLsizei len
Definition: glext.h:3285
GLuint64 key
Definition: glext.h:8966
int HID_API_EXPORT_CALL hid_get_indexed_string(hidapi_device *dev, int string_index, wchar_t *string, size_t maxlen)
Get a string from a HID device, based on its string index.
Definition: hidapi.cpp:1006
static io_service_t hidapi_IOHIDDeviceGetService(IOHIDDeviceRef device)
Definition: hidapi.cpp:275
int HID_API_EXPORT hid_exit(void)
Finalize the HIDAPI library.
Definition: hidapi.cpp:353
static int pthread_barrier_wait(pthread_barrier_t *barrier)
Definition: hidapi.cpp:56
wchar_t * product_string
Definition: hidapi.h:64
static void hid_report_callback(void *context, IOReturn result, void *sender, IOHIDReportType report_type, uint32_t report_id, uint8_t *report, CFIndex report_length)
Definition: hidapi.cpp:535
const GLubyte * c
Definition: glext.h:12690
size_t len
Definition: hidapi.cpp:80
int uses_numbered_reports
Definition: hidapi.cpp:87
unsigned int uint32_t
Definition: stdint.h:80
_W64 unsigned int uintptr_t
Definition: stdint.h:119
struct input_report * next
Definition: hidapi.cpp:81
static int cond_wait(const hidapi_device *dev, pthread_cond_t *cond, pthread_mutex_t *mutex)
Definition: hidapi.cpp:792
pthread_barrier_t barrier
Definition: hidapi.cpp:99
int HID_API_EXPORT hid_set_nonblocking(hidapi_device *dev, int nonblock)
Set the device handle to be non-blocking.
Definition: hidapi.cpp:912
unsigned short release_number
Definition: hidapi.h:60
static int get_product_string(IOHIDDeviceRef device, wchar_t *buf, size_t len)
Definition: hidapi.cpp:253
GLuint GLfloat x0
Definition: glext.h:9721
static int cond_timedwait(const hidapi_device *dev, pthread_cond_t *cond, pthread_mutex_t *mutex, const struct timespec *abstime)
Definition: hidapi.cpp:812
static int32_t get_int_property(IOHIDDeviceRef device, CFStringRef key)
Definition: hidapi.cpp:171
int HID_API_EXPORT hid_read(hidapi_device *dev, unsigned char *data, size_t length)
Read an Input report from a HID device.
Definition: hidapi.cpp:907
int HID_API_EXPORT hid_init(void)
Initialize the HIDAPI library.
Definition: hidapi.cpp:343
static void process_pending_events(void)
Definition: hidapi.cpp:365
pthread_t thread
Definition: hidapi.cpp:96
static int32_t get_location_id(IOHIDDeviceRef device)
Definition: hidapi.cpp:1022
static hidapi_device * new_hid_device(void)
Definition: hidapi.cpp:104
hidapi_device *HID_API_EXPORT hid_open(unsigned short vendor_id, unsigned short product_id, const wchar_t *serial_number)
Open a HID device using a Vendor ID (VID), Product ID (PID) and optionally a serial number...
Definition: hidapi.cpp:486
#define HID_API_EXPORT_CALL
Definition: hidapi.h:40
void next(auto_any_t cur, type2type< T, C > *)
Definition: foreach.hpp:757
unsigned short usage_page
Definition: hidapi.h:67
CFStringRef run_loop_mode
Definition: hidapi.cpp:89
GLenum type
static int get_manufacturer_string(IOHIDDeviceRef device, wchar_t *buf, size_t len)
Definition: hidapi.cpp:248
GLenum GLfloat param
uint8_t * input_report_buf
Definition: hidapi.cpp:92
GLint GLsizei count
GLint ref
static void hid_device_removal_callback(void *context, IOReturn result, void *sender)
Definition: hidapi.cpp:522
static int init_hid_manager(void)
Definition: hidapi.cpp:327
int HID_API_EXPORT_CALL hid_get_product_string(hidapi_device *dev, wchar_t *string, size_t maxlen)
Get The Product String from a HID device.
Definition: hidapi.cpp:996
int blocking
Definition: hidapi.cpp:86
GLsizei range
#define NULL
Definition: tinycthread.c:47
int i
GLenum GLuint GLenum GLsizei length
GLuint res
Definition: glext.h:8856
static int set_report(hidapi_device *dev, IOHIDReportType type, const unsigned char *data, size_t length)
Definition: hidapi.cpp:734
static int pthread_barrier_destroy(pthread_barrier_t *barrier)
Definition: hidapi.cpp:49
unsigned short vendor_id
Definition: hidapi.h:53
HID_API_EXPORT const wchar_t *HID_API_CALL hid_error(hidapi_device *dev)
Get a string describing the last error which occurred.
Definition: hidapi.cpp:1014
signed int int32_t
Definition: stdint.h:77
::std_msgs::UInt8_< std::allocator< void > > UInt8
Definition: UInt8.h:47
struct hidapi_device_info HID_API_EXPORT * hid_enumerate(unsigned short vendor_id, unsigned short product_id)
Enumerate the HID Devices.
Definition: hidapi.cpp:372
static void * read_thread(void *param)
Definition: hidapi.cpp:591
root
Definition: repo.py:7
#define FALSE
Definition: tinycthread.c:53
GLboolean * data
int HID_API_EXPORT hid_get_feature_report(hidapi_device *dev, unsigned char *data, size_t length)
Get a feature report from a HID device.
Definition: hidapi.cpp:925
#define BUF_LEN
static void free_hid_device(hidapi_device *dev)
Definition: hidapi.cpp:127
GLuint64EXT * result
Definition: glext.h:10921
int HID_API_EXPORT hid_send_feature_report(hidapi_device *dev, const unsigned char *data, size_t length)
Send a Feature report to the device.
Definition: hidapi.cpp:920
int interface_number
Definition: hidapi.h:75
auto device
Definition: pyrs_net.cpp:17
hidapi_device *HID_API_EXPORT hid_open_path(const char *path)
Open a HID device by its path name.
Definition: hidapi.cpp:660
#define HID_API_CALL
Definition: hidapi.h:37
Definition: parser.hpp:150
struct pthread_barrier pthread_barrier_t
wchar_t * manufacturer_string
Definition: hidapi.h:62
static void perform_signal_callback(void *context)
Definition: hidapi.cpp:585


librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:47:16