usb_libusb10.c
Go to the documentation of this file.
1 /*
2  * This file is part of the OpenKinect Project. http://www.openkinect.org
3  *
4  * Copyright (c) 2010 individual OpenKinect contributors. See the CONTRIB file
5  * for details.
6  *
7  * This code is licensed to you under the terms of the Apache License, version
8  * 2.0, or, at your option, the terms of the GNU General Public License,
9  * version 2.0. See the APACHE20 and GPL2 files for the text of the licenses,
10  * or the following URLs:
11  * http://www.apache.org/licenses/LICENSE-2.0
12  * http://www.gnu.org/licenses/gpl-2.0.txt
13  *
14  * If you redistribute this file in source form, modified or unmodified, you
15  * may:
16  * 1) Leave this header intact and distribute it under the same terms,
17  * accompanying it with the APACHE20 and GPL20 files, or
18  * 2) Delete the Apache 2.0 clause and accompany it with the GPL2 file, or
19  * 3) Delete the GPL v2 clause and accompany it with the APACHE20 file
20  * In all cases you must keep the copyright notice intact and include a copy
21  * of the CONTRIB file.
22  *
23  * Binary distributions must follow the binary distribution requirements of
24  * either License.
25  */
26 
27 #include <stdio.h>
28 #include <stdlib.h>
29 #include <string.h>
30 #include <unistd.h>
31 #include <libusb.h>
32 #include "freenect_internal.h"
33 #include "loader.h"
34 
35 #ifdef _MSC_VER
36  # define sleep(x) Sleep((x)*1000)
37 #endif
38 
39 
41 {
42  libusb_device **devs;
43  //pointer to pointer of device, used to retrieve a list of devices
44  ssize_t cnt = libusb_get_device_list (ctx->ctx, &devs);
45  //get the list of devices
46  if (cnt < 0)
47  return (-1);
48  int nr = 0, i = 0;
49  struct libusb_device_descriptor desc;
50  for (i = 0; i < cnt; ++i)
51  {
52  int r = libusb_get_device_descriptor (devs[i], &desc);
53  if (r < 0)
54  continue;
55  if (desc.idVendor == VID_MICROSOFT && (desc.idProduct == PID_NUI_CAMERA || desc.idProduct == PID_K4W_CAMERA))
56  nr++;
57  }
58  libusb_free_device_list (devs, 1);
59  // free the list, unref the devices in it
60  return nr;
61 }
62 
63 // Returns 1 if `pid` identifies K4W audio, 0 otherwise
65 {
66  return (pid == PID_K4W_AUDIO || pid == PID_K4W_AUDIO_ALT_1 || pid == PID_K4W_AUDIO_ALT_2);
67 }
68 
70 {
71  if (cnt <= 0) return NULL;
72 
73  int cameraBusNo = libusb_get_bus_number(camera);
74  if (cameraBusNo < 0) return NULL;
75  libusb_device * cameraParent = libusb_get_parent(camera);
76 
77  int i = 0;
78  for (i = 0; i < cnt; i++)
79  {
80  struct libusb_device_descriptor desc;
81  int res = libusb_get_device_descriptor (deviceList[i], &desc);
82  if (res < 0)
83  {
84  continue;
85  }
86 
87  if (desc.idVendor == VID_MICROSOFT)
88  {
89  // make sure its some type of Kinect audio device
91  {
92  int audioBusNo = libusb_get_bus_number(deviceList[i]);
93  if (audioBusNo == cameraBusNo)
94  {
95  // we have a match!
96  // let's double check
97  libusb_device * audioParent = libusb_get_parent(deviceList[i]);
98  if (cameraParent == audioParent)
99  {
100  return deviceList[i];
101  }
102  }
103  }
104  }
105  }
106 
107  return NULL;
108 }
109 
111 {
112  // todo: figure out how to log without freenect_context
113 
114  *attribute_list = NULL; // initialize some return value in case the user is careless.
115  libusb_device **devs; // pointer to pointer of device, used to retrieve a list of devices
116  ssize_t count = libusb_get_device_list (ctx->ctx, &devs);
117  if (count < 0)
118  {
119  return -1;
120  }
121 
122  struct freenect_device_attributes** next_attr = attribute_list;
123 
124  // Pass over the list. For each camera seen, if we already have a camera
125  // for the newest_camera device, allocate a new one and append it to the list,
126  // incrementing num_cams.
127  int num_cams = 0;
128  int i;
129  for (i = 0; i < count; i++)
130  {
131  libusb_device* camera_device = devs[i];
132 
133  struct libusb_device_descriptor desc;
134  int res = libusb_get_device_descriptor (camera_device, &desc);
135  if (res < 0)
136  {
137  continue;
138  }
139 
140  if (desc.idVendor == VID_MICROSOFT && (desc.idProduct == PID_NUI_CAMERA || desc.idProduct == PID_K4W_CAMERA))
141  {
142  // Verify that a serial number exists to query. If not, don't touch the device.
143  if (desc.iSerialNumber == 0)
144  {
145  continue;
146  }
147 
148  libusb_device_handle *camera_handle;
149  res = libusb_open(camera_device, &camera_handle);
150  if (res != 0)
151  {
152  continue;
153  }
154 
155  // Read string descriptor referring to serial number.
156  unsigned char serial[256]; // String descriptors are at most 256 bytes.
157  res = libusb_get_string_descriptor_ascii(camera_handle, desc.iSerialNumber, serial, 256);
158  libusb_close(camera_handle);
159  if (res < 0)
160  {
161  continue;
162  }
163 
164  // K4W and 1473 don't provide a camera serial; use audio serial instead.
165  const char* const K4W_1473_SERIAL = "0000000000000000";
166  if (strncmp((const char*)serial, K4W_1473_SERIAL, 16) == 0)
167  {
168  libusb_device* audio_device = fnusb_find_connected_audio_device(camera_device, devs, count);
169 
170  if (audio_device != NULL)
171  {
172  struct libusb_device_descriptor audio_desc;
173  res = libusb_get_device_descriptor(audio_device, &audio_desc);
174  if (res != 0)
175  {
176  //FN_ERROR("Failed to get audio serial descriptors of K4W or 1473 device: %d\n", res);
177  }
178  else
179  {
180  libusb_device_handle * audio_handle = NULL;
181  res = libusb_open(audio_device, &audio_handle);
182  if (res != 0)
183  {
184  //FN_ERROR("Failed to open audio device for serial of K4W or 1473 device: %d\n", res);
185  }
186  else
187  {
188  res = libusb_get_string_descriptor_ascii(audio_handle, audio_desc.iSerialNumber, serial, 256);
189  libusb_close(audio_handle);
190  if (res != 0)
191  {
192  //FN_ERROR("Failed to get audio serial of K4W or 1473 device: %d\n", res);
193  }
194  }
195  }
196  }
197  }
198 
199  // Add item to linked list.
200  struct freenect_device_attributes* current_attr = (struct freenect_device_attributes*)malloc(sizeof(struct freenect_device_attributes));
201  memset(current_attr, 0, sizeof(*current_attr));
202 
203  current_attr->camera_serial = strdup((char*)serial);
204  *next_attr = current_attr;
205  next_attr = &(current_attr->next);
206  num_cams++;
207  }
208  }
209 
210  libusb_free_device_list(devs, 1);
211  return num_cams;
212 }
213 
215 {
216  int res;
217  if (!usb_ctx) {
218  res = libusb_init(&ctx->ctx);
219  if (res >= 0) {
220  ctx->should_free_ctx = 1;
221  return 0;
222  } else {
223  ctx->should_free_ctx = 0;
224  ctx->ctx = NULL;
225  return res;
226  }
227  } else {
228  // explicit cast required: in WIN32, freenect_usb_context* maps to void*
229  ctx->ctx = (libusb_context*)usb_ctx;
230  ctx->should_free_ctx = 0;
231  return 0;
232  }
233 }
234 
236 {
237  //int res;
238  if (ctx->should_free_ctx) {
239  libusb_exit(ctx->ctx);
240  ctx->ctx = NULL;
241  }
242  return 0;
243 }
244 
246 {
247  return libusb_handle_events(ctx->ctx);
248 }
249 
251 {
252  return libusb_handle_events_timeout(ctx->ctx, timeout);
253 }
254 
256 {
257  freenect_context *ctx = dev->parent;
258 
261 
262  dev->usb_cam.parent = dev;
263  dev->usb_cam.dev = NULL;
264  dev->usb_motor.parent = dev;
265  dev->usb_motor.dev = NULL;
266  dev->usb_audio.parent = dev;
267  dev->usb_audio.dev = NULL;
268 
269  libusb_device **devs; // pointer to pointer of device, used to retrieve a list of devices
270  ssize_t cnt = libusb_get_device_list (dev->parent->usb.ctx, &devs); //get the list of devices
271  if (cnt < 0)
272  return -1;
273 
274  int i = 0, nr_cam = 0, nr_mot = 0;
275  int nr_audio = 0;
276  int res;
277  struct libusb_device_descriptor desc;
278 
279  for (i = 0; i < cnt; i++)
280  {
281  int r = libusb_get_device_descriptor (devs[i], &desc);
282  if (r < 0)
283  continue;
284 
285  if (desc.idVendor != VID_MICROSOFT)
286  continue;
287  res = 0;
288  // Search for the camera
290  {
291  // If the index given by the user matches our camera index
292  if (nr_cam == index)
293  {
294  res = libusb_open (devs[i], &dev->usb_cam.dev);
295  if (res < 0 || !dev->usb_cam.dev)
296  {
297  FN_ERROR("Could not open camera: %d\n", res);
298  dev->usb_cam.dev = NULL;
299  break;
300  }
301  if (desc.idProduct == PID_K4W_CAMERA || desc.bcdDevice != fn_le32(267))
302  {
303  freenect_device_flags requested_devices = ctx->enabled_subdevices;
304 
305  // Not the 1414 kinect so remove the motor flag, this should preserve the audio flag if set
307 
308  ctx->zero_plane_res = 334;
310 
311  // set the LED for non 1414 devices to keep the camera alive for some systems which get freezes
312 
313  libusb_device * audioDevice = fnusb_find_connected_audio_device(devs[i], devs, cnt);
314  if (audioDevice != NULL)
315  {
316  libusb_device_handle * audioHandle = NULL;
317  res = libusb_open(audioDevice, &audioHandle);
318 
319  if (res != 0)
320  {
321  FN_ERROR("Failed to set the LED of K4W or 1473 device: %d\n", res);
322  }
323  else
324  {
325  // we need to do this as it is possible that the device was not closed properly in a previous session
326  // if we don't do this and the device wasn't closed properly - it can cause infinite hangs on LED and TILT functions
327  libusb_reset_device(audioHandle);
328  libusb_close(audioHandle);
329 
330  res = libusb_open(audioDevice, &audioHandle);
331  if (res == 0)
332  {
333  res = libusb_claim_interface(audioHandle, 0);
334  if (res != 0)
335  {
336  FN_ERROR("Unable to claim interface %d\n", res);
337  }
338  else
339  {
340  fnusb_set_led_alt(audioHandle, ctx, LED_GREEN);
341  libusb_release_interface(audioHandle, 0);
342  }
343  libusb_close(audioHandle);
344  }
345  }
346  }
347  // for newer devices we need to enable the audio device for motor control
348  // we only do this though if motor has been requested.
349  if ((requested_devices & FREENECT_DEVICE_MOTOR) && (requested_devices & FREENECT_DEVICE_AUDIO) == 0)
350  {
351  ctx->enabled_subdevices = (freenect_device_flags)(ctx->enabled_subdevices | FREENECT_DEVICE_AUDIO);
352  }
353  }
354  else
355  {
356  // The good old kinect that tilts and tweets
357  ctx->zero_plane_res = 322;
358  }
359 
360 #ifndef _WIN32
361  // Detach an existing kernel driver for the device
362  res = libusb_kernel_driver_active(dev->usb_cam.dev, 0);
363  if (res == 1)
364  {
365  res = libusb_detach_kernel_driver(dev->usb_cam.dev, 0);
366  if (res < 0)
367  {
368  FN_ERROR("Could not detach kernel driver for camera: %d\n", res);
369  libusb_close(dev->usb_cam.dev);
370  dev->usb_cam.dev = NULL;
371  break;
372  }
373  }
374 #endif
375  res = libusb_claim_interface (dev->usb_cam.dev, 0);
376  if (res < 0)
377  {
378  FN_ERROR("Could not claim interface on camera: %d\n", res);
379  libusb_close(dev->usb_cam.dev);
380  dev->usb_cam.dev = NULL;
381  break;
382  }
383  if (desc.idProduct == PID_K4W_CAMERA)
384  {
385  res = libusb_set_interface_alt_setting(dev->usb_cam.dev, 0, 1);
386  if (res != 0)
387  {
388  FN_ERROR("Failed to set alternate interface #1 for K4W: %d\n", res);
389  libusb_close(dev->usb_cam.dev);
390  dev->usb_cam.dev = NULL;
391  break;
392  }
393  }
394  }
395  else
396  {
397  nr_cam++;
398  }
399  }
400  }
401 
402  if (ctx->enabled_subdevices == FREENECT_DEVICE_CAMERA || res < 0)
403  cnt = 0;
404 
405  // Search for the motor
406  for (i = 0; i < cnt; i++)
407  {
408  int r = libusb_get_device_descriptor (devs[i], &desc);
409  if (r < 0)
410  continue;
411 
412  if (desc.idVendor != VID_MICROSOFT)
413  continue;
415  {
416  // If the index given by the user matches our camera index
417  if (nr_mot == index)
418  {
419  res = libusb_open (devs[i], &dev->usb_motor.dev);
420  if (res < 0 || !dev->usb_motor.dev)
421  {
422  FN_ERROR("Could not open motor: %d\n", res);
423  dev->usb_motor.dev = NULL;
424  break;
425  }
426  res = libusb_claim_interface (dev->usb_motor.dev, 0);
427  if (res < 0)
428  {
429  FN_ERROR("Could not claim interface on motor: %d\n", res);
430  libusb_close(dev->usb_motor.dev);
431  dev->usb_motor.dev = NULL;
432  break;
433  }
434  }
435  else
436  {
437  nr_mot++;
438  }
439  }
440 
441  // Search for the audio
443  {
444  // If the index given by the user matches our audio index
445  if (nr_audio == index)
446  {
447  res = libusb_open (devs[i], &dev->usb_audio.dev);
448  if (res < 0 || !dev->usb_audio.dev)
449  {
450  FN_ERROR("Could not open audio: %d\n", res);
451  dev->usb_audio.dev = NULL;
452  break;
453  }
454  res = libusb_claim_interface (dev->usb_audio.dev, 0);
455  if (res < 0)
456  {
457  FN_ERROR("Could not claim interface on audio: %d\n", res);
458  libusb_close(dev->usb_audio.dev);
459  dev->usb_audio.dev = NULL;
460  break;
461  }
462 
463  // Using the device handle that we've claimed, see if this
464  // device has already uploaded firmware (has 2 interfaces).
465  // If not, save the serial number (by reading the appropriate
466  // descriptor), upload the firmware, and then enter a loop
467  // waiting for a device with the same serial number to
468  // reappear.
469  int num_interfaces = fnusb_num_interfaces(&dev->usb_audio);
470 
471  if (num_interfaces >= 2)
472  {
474  {
476  }
477  }
478  else
479  {
480  // Read the serial number from the string descriptor and save it.
481  unsigned char string_desc[256]; // String descriptors are at most 256 bytes
482  res = libusb_get_string_descriptor_ascii(dev->usb_audio.dev, desc.iSerialNumber, string_desc, 256);
483  if (res < 0)
484  {
485  FN_ERROR("Failed to retrieve serial number for audio device in bootloader state\n");
486  break;
487  }
488  char* audio_serial = strdup((char*)string_desc);
489 
490  FN_SPEW("Uploading firmware to audio device in bootloader state.\n");
491 
492  // Check if we can load from memory - otherwise load from disk
493  if (desc.idProduct == PID_NUI_AUDIO && ctx->fn_fw_nui_ptr && ctx->fn_fw_nui_size > 0)
494  {
495  FN_SPEW("loading firmware from memory\n");
497  }
498  else if (desc.idProduct == PID_K4W_AUDIO && ctx->fn_fw_k4w_ptr && ctx->fn_fw_k4w_size > 0)
499  {
500  FN_SPEW("loading firmware from memory\n");
502  }
503  else
504  {
505  res = upload_firmware(&dev->usb_audio, "audios.bin");
506  }
507 
508  if (res < 0)
509  {
510  FN_ERROR("upload_firmware failed: %d\n", res);
511  break;
512  }
513  libusb_close(dev->usb_audio.dev);
514  dev->usb_audio.dev = NULL;
515  // Wait for the device to reappear.
516  int loops = 0;
517  for (loops = 0; loops < 10; loops++)
518  {
519  FN_SPEW("Try %d: Looking for new audio device matching serial %s\n", loops, audio_serial);
520  // Scan devices.
521  libusb_device **new_dev_list;
522  int dev_index;
523  ssize_t num_new_devs = libusb_get_device_list(ctx->usb.ctx, &new_dev_list);
524  for (dev_index = 0; dev_index < num_new_devs; ++dev_index)
525  {
526  struct libusb_device_descriptor new_dev_desc;
527  int r;
528  r = libusb_get_device_descriptor (new_dev_list[dev_index], &new_dev_desc);
529  if (r < 0)
530  continue;
531  // If this dev is a Kinect audio device, open device, read serial, and compare.
532  if (new_dev_desc.idVendor == VID_MICROSOFT && (new_dev_desc.idProduct == PID_NUI_AUDIO || fnusb_is_pid_k4w_audio(desc.idProduct)))
533  {
534  FN_SPEW("Matched VID/PID!\n");
535  libusb_device_handle* new_dev_handle;
536  // Open device
537  r = libusb_open(new_dev_list[dev_index], &new_dev_handle);
538  if (r < 0)
539  continue;
540  // Read serial
541  r = libusb_get_string_descriptor_ascii(new_dev_handle, new_dev_desc.iSerialNumber, string_desc, 256);
542  if (r < 0)
543  {
544  FN_SPEW("Lost new audio device while fetching serial number.\n");
545  libusb_close(new_dev_handle);
546  continue;
547  }
548  // Compare to expected serial
549  if (r == strlen(audio_serial) && strcmp((char*)string_desc, audio_serial) == 0)
550  {
551  // We found it!
552  r = libusb_claim_interface(new_dev_handle, 0);
553  if (r != 0)
554  {
555  // Ouch, found the device but couldn't claim the interface.
556  FN_SPEW("Device with serial %s reappeared but couldn't claim interface 0\n", audio_serial);
557  libusb_close(new_dev_handle);
558  continue;
559  }
560  // Save the device handle.
561  dev->usb_audio.dev = new_dev_handle;
562 
563  // Verify that we've actually found a device running the right firmware.
564  num_interfaces = fnusb_num_interfaces(&dev->usb_audio);
565 
566  if (num_interfaces >= 2)
567  {
569  {
571  }
572  }
573  else
574  {
575  FN_SPEW("Opened audio with matching serial but too few interfaces.\n");
576  dev->usb_audio.dev = NULL;
577  libusb_close(new_dev_handle);
578  continue;
579  } break;
580  }
581  else
582  {
583  FN_SPEW("Got serial %s, expected serial %s\n", (char*)string_desc, audio_serial);
584  }
585  }
586  }
587 
588  libusb_free_device_list(new_dev_list, 1);
589  // If we found the right device, break out of this loop.
590  if (dev->usb_audio.dev)
591  break;
592  // Sleep for a second to give the device more time to reenumerate.
593  sleep(1);
594  }
595  free(audio_serial);
596  }
597  }
598  else
599  {
600  nr_audio++;
601  }
602  }
603  }
604 
605  libusb_free_device_list (devs, 1); // free the list, unref the devices in it
606 
607  // Check that each subdevice is either opened or not enabled.
608  if ((dev->usb_cam.dev || !(ctx->enabled_subdevices & FREENECT_DEVICE_CAMERA))
610  && (dev->usb_audio.dev || !(ctx->enabled_subdevices & FREENECT_DEVICE_AUDIO)))
611  {
612  return 0;
613  }
614  else
615  {
616  if (dev->usb_cam.dev)
617  {
619  libusb_close(dev->usb_cam.dev);
620  }
621  else
622  {
623  FN_ERROR("Failed to open camera subdevice or it is not disabled.");
624  }
625 
626  if (dev->usb_motor.dev)
627  {
629  libusb_close(dev->usb_motor.dev);
630  }
631  else
632  {
633  FN_ERROR("Failed to open motor subddevice or it is not disabled.");
634  }
635 
636  if (dev->usb_audio.dev)
637  {
639  libusb_close(dev->usb_audio.dev);
640  }
641  else
642  {
643  FN_ERROR("Failed to open audio subdevice or it is not disabled.");
644  }
645 
646  return -1;
647  }
648 }
649 
651 {
652  if (dev->usb_cam.dev) {
654 #ifndef _WIN32
655  libusb_attach_kernel_driver(dev->usb_cam.dev, 0);
656 #endif
657  libusb_close(dev->usb_cam.dev);
658  dev->usb_cam.dev = NULL;
659  }
660  if (dev->usb_motor.dev) {
662  libusb_close(dev->usb_motor.dev);
663  dev->usb_motor.dev = NULL;
664  }
665  if (dev->usb_audio.dev) {
667  libusb_close(dev->usb_audio.dev);
668  dev->usb_audio.dev = NULL;
669  }
670  return 0;
671 }
672 
673 static void LIBUSB_CALL iso_callback(struct libusb_transfer *xfer)
674 {
675  int i;
678 
679  if (strm->dead) {
680  strm->dead_xfers++;
681  FN_SPEW("EP %02x transfer complete, %d left\n", xfer->endpoint, strm->num_xfers - strm->dead_xfers);
682  return;
683  }
684 
685  switch(xfer->status) {
686  case LIBUSB_TRANSFER_COMPLETED: // Normal operation.
687  {
688  uint8_t *buf = (uint8_t*)xfer->buffer;
689  for (i=0; i<strm->pkts; i++) {
690  strm->cb(strm->parent->parent, buf, xfer->iso_packet_desc[i].actual_length);
691  buf += strm->len;
692  }
693  int res;
694  res = libusb_submit_transfer(xfer);
695  if (res != 0) {
696  FN_ERROR("iso_callback(): failed to resubmit transfer after successful completion: %d\n", res);
697  strm->dead_xfers++;
698  if (res == LIBUSB_ERROR_NO_DEVICE) {
699  strm->parent->device_dead = 1;
700  }
701  }
702  break;
703  }
705  {
706  // We lost the device we were talking to. This is a large problem,
707  // and one that we should eventually come up with a way to
708  // properly propagate up to the caller.
709  if(!strm->parent->device_dead) {
710  FN_ERROR("USB device disappeared, cancelling stream %02x :(\n", xfer->endpoint);
711  }
712  strm->dead_xfers++;
713  strm->parent->device_dead = 1;
714  break;
715  }
717  {
718  if(strm->dead) {
719  FN_SPEW("EP %02x transfer cancelled\n", xfer->endpoint);
720  } else {
721  // This seems to be a libusb bug on OSX - instead of completing
722  // the transfer with LIBUSB_TRANSFER_NO_DEVICE, the transfers
723  // simply come back cancelled by the OS. We can detect this,
724  // though - the stream should be marked dead if we're
725  // intentionally cancelling transfers.
726  if(!strm->parent->device_dead) {
727  FN_ERROR("Got cancelled transfer, but we didn't request it - device disconnected?\n");
728  }
729  strm->parent->device_dead = 1;
730  }
731  strm->dead_xfers++;
732  break;
733  }
734  default:
735  {
736  // On other errors, resubmit the transfer - in particular, libusb
737  // on OSX tends to hit random errors a lot. If we don't resubmit
738  // the transfers, eventually all of them die and then we don't get
739  // any more data from the Kinect.
740  FN_WARNING("Isochronous transfer error: %d\n", xfer->status);
741  int res;
742  res = libusb_submit_transfer(xfer);
743  if (res != 0) {
744  FN_ERROR("Isochronous transfer resubmission failed after unknown error: %d\n", res);
745  strm->dead_xfers++;
746  if (res == LIBUSB_ERROR_NO_DEVICE) {
747  strm->parent->device_dead = 1;
748  }
749  }
750  break;
751  }
752  }
753 }
754 
755 FN_INTERNAL int fnusb_start_iso(fnusb_dev *dev, fnusb_isoc_stream *strm, fnusb_iso_cb cb, int ep, int xfers, int pkts, int len)
756 {
758  int ret, i;
759 
760  strm->parent = dev;
761  strm->cb = cb;
762  strm->num_xfers = xfers;
763  strm->pkts = pkts;
764  strm->len = len;
765  strm->buffer = (uint8_t*)malloc(xfers * pkts * len);
766  strm->xfers = (struct libusb_transfer**)malloc(sizeof(struct libusb_transfer*) * xfers);
767  strm->dead = 0;
768  strm->dead_xfers = 0;
769 
770  uint8_t *bufp = strm->buffer;
771 
772  for (i=0; i<xfers; i++) {
773  FN_SPEW("Creating EP %02x transfer #%d\n", ep, i);
774  strm->xfers[i] = libusb_alloc_transfer(pkts);
775 
776  libusb_fill_iso_transfer(strm->xfers[i], dev->dev, ep, bufp, pkts * len, pkts, iso_callback, strm, 0);
777 
778  libusb_set_iso_packet_lengths(strm->xfers[i], len);
779 
780  ret = libusb_submit_transfer(strm->xfers[i]);
781  if (ret < 0) {
782  FN_WARNING("Failed to submit isochronous transfer %d: %d\n", i, ret);
783  strm->dead_xfers++;
784  }
785 
786  bufp += pkts*len;
787  }
788 
789  return 0;
790 
791 }
792 
794 {
796  int i;
797 
798  FN_FLOOD("fnusb_stop_iso() called\n");
799 
800  strm->dead = 1;
801 
802  for (i=0; i<strm->num_xfers; i++)
803  libusb_cancel_transfer(strm->xfers[i]);
804  FN_FLOOD("fnusb_stop_iso() cancelled all transfers\n");
805 
806  while (strm->dead_xfers < strm->num_xfers) {
807  FN_FLOOD("fnusb_stop_iso() dead = %d\tnum = %d\n", strm->dead_xfers, strm->num_xfers);
809  }
810 
811  for (i=0; i<strm->num_xfers; i++)
812  libusb_free_transfer(strm->xfers[i]);
813  FN_FLOOD("fnusb_stop_iso() freed all transfers\n");
814 
815  free(strm->buffer);
816  free(strm->xfers);
817 
818  FN_FLOOD("fnusb_stop_iso() freed buffers and stream\n");
819  FN_FLOOD("fnusb_stop_iso() done\n");
820  return 0;
821 }
822 
823 FN_INTERNAL int fnusb_control(fnusb_dev *dev, uint8_t bmRequestType, uint8_t bRequest, uint16_t wValue, uint16_t wIndex, uint8_t *data, uint16_t wLength)
824 {
825  return libusb_control_transfer(dev->dev, bmRequestType, bRequest, wValue, wIndex, data, wLength, 0);
826 }
827 
828 FN_INTERNAL int fnusb_bulk(fnusb_dev *dev, uint8_t endpoint, uint8_t *data, int len, int *transferred) {
829  *transferred = 0;
830  return libusb_bulk_transfer(dev->dev, endpoint, data, len, transferred, 0);
831 }
832 
834  int retval = 0;
835  int res;
836  libusb_device* d = libusb_get_device(dev->dev);
837  struct libusb_config_descriptor* config;
838  res = libusb_get_active_config_descriptor(d, &config);
839  if (res < 0) // Something went wrong
840  return res;
841  retval = config->bNumInterfaces;
842  libusb_free_config_descriptor(config);
843  return retval;
844 }
#define VID_MICROSOFT
FN_INTERNAL int fnusb_bulk(fnusb_dev *dev, uint8_t endpoint, uint8_t *data, int len, int *transferred)
Definition: usb_libusb10.c:828
freenect_device_flags enabled_subdevices
int libusb_handle_events_timeout(libusb_context *ctx, struct timeval *timeout)
Definition: libusbemu.cpp:638
FN_INTERNAL int fnusb_open_subdevices(freenect_device *dev, int index)
Definition: usb_libusb10.c:255
int libusb_handle_events(libusb_context *ctx)
Definition: libusbemu.cpp:622
void libusb_set_iso_packet_lengths(struct libusb_transfer *transfer, unsigned int length)
Definition: libusbemu.cpp:516
fnusb_iso_cb cb
Definition: usb_libusb10.h:78
freenect_context * parent
unsigned char * fn_fw_k4w_ptr
int libusb_get_device_descriptor(libusb_device *dev, struct libusb_device_descriptor *desc)
Definition: libusbemu.cpp:206
FN_INTERNAL int fnusb_start_iso(fnusb_dev *dev, fnusb_isoc_stream *strm, fnusb_iso_cb cb, int ep, int xfers, int pkts, int len)
Definition: usb_libusb10.c:755
int device_does_motor_control_with_audio
#define PID_NUI_MOTOR
enum libusb_transfer_status status
Definition: libusb.h:163
FN_INTERNAL libusb_device * fnusb_find_connected_audio_device(libusb_device *camera, libusb_device **deviceList, int cnt)
Definition: usb_libusb10.c:69
long ssize_t
Definition: unistd.h:36
unsigned short uint16_t
unsigned int fn_fw_k4w_size
void freenect_usb_context
Definition: libfreenect.h:182
#define FN_ERROR(...)
#define FN_FLOOD(...)
const char * camera_serial
Definition: libfreenect.h:70
FN_INTERNAL int fnusb_stop_iso(fnusb_dev *dev, fnusb_isoc_stream *strm)
Definition: usb_libusb10.c:793
int libusb_init(libusb_context **context)
Definition: libusbemu.cpp:88
uint8_t * buffer
Definition: usb_libusb10.h:77
FN_INTERNAL int upload_firmware(fnusb_dev *dev, char *filename)
Definition: loader.c:125
unsigned char * buffer
Definition: libusb.h:168
int should_free_ctx
Definition: usb_libusb10.h:65
unsigned char uint8_t
#define PID_K4W_CAMERA
void libusb_free_device_list(libusb_device **list, int unref_devices)
Definition: libusbemu.cpp:190
int device_dead
Definition: usb_libusb10.h:71
FN_INTERNAL int fnusb_num_interfaces(fnusb_dev *dev)
Definition: usb_libusb10.c:833
FN_INTERNAL int fnusb_set_led_alt(libusb_device_handle *dev, freenect_context *ctx, freenect_led_options state)
Definition: tilt.c:239
int libusb_open(libusb_device *dev, libusb_device_handle **handle)
Definition: libusbemu.cpp:217
libusb_device_handle * dev
Definition: usb_libusb10.h:70
unsigned int actual_length
Definition: libusb.h:176
#define FN_WARNING(...)
struct libusb_transfer * libusb_alloc_transfer(int iso_packets)
Definition: libusbemu.cpp:439
FN_INTERNAL int fnusb_close_subdevices(freenect_device *dev)
Definition: usb_libusb10.c:650
void libusb_close(libusb_device_handle *dev_handle)
Definition: libusbemu.cpp:249
fnusb_dev * parent
Definition: usb_libusb10.h:75
#define PID_K4W_AUDIO_ALT_2
int libusb_release_interface(libusb_device_handle *dev, int interface_number)
Definition: libusbemu.cpp:347
#define PID_NUI_AUDIO
void(* fnusb_iso_cb)(freenect_device *dev, uint8_t *buf, int len)
unsigned char * fn_fw_nui_ptr
int libusb_control_transfer(libusb_device_handle *dev_handle, uint8_t bmRequestType, uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigned char *data, uint16_t wLength, unsigned int timeout)
Definition: libusbemu.cpp:394
FN_INTERNAL int fnusb_list_device_attributes(fnusb_ctx *ctx, struct freenect_device_attributes **attribute_list)
Definition: usb_libusb10.c:110
FN_INTERNAL int fnusb_control(fnusb_dev *dev, uint8_t bmRequestType, uint8_t bRequest, uint16_t wValue, uint16_t wIndex, uint8_t *data, uint16_t wLength)
Definition: usb_libusb10.c:823
void * user_data
Definition: libusb.h:167
void libusb_free_transfer(struct libusb_transfer *transfer)
Definition: libusbemu.cpp:451
FN_INTERNAL int upload_firmware_from_memory(fnusb_dev *dev, unsigned char *fw_from_mem, unsigned int fw_size_in_btyes)
Definition: loader.c:233
struct libusb_iso_packet_descriptor * iso_packet_desc
Definition: libusb.h:170
#define FN_SPEW(...)
freenect_device * parent
Definition: usb_libusb10.h:69
struct freenect_device_attributes * next
Definition: libfreenect.h:69
ssize_t libusb_get_device_list(libusb_context *ctx, libusb_device ***list)
Definition: libusbemu.cpp:151
FN_INTERNAL int fnusb_shutdown(fnusb_ctx *ctx)
Definition: usb_libusb10.c:235
#define PID_K4W_AUDIO
void libusb_fill_iso_transfer(struct libusb_transfer *transfer, libusb_device_handle *dev_handle, unsigned char endpoint, unsigned char *buffer, int length, int num_iso_packets, libusb_transfer_cb_fn callback, void *user_data, unsigned int timeout)
Definition: libusbemu.cpp:489
int libusb_get_string_descriptor_ascii(libusb_device_handle *dev_handle, uint8_t desc_index, unsigned char *data, int length)
Definition: libusbemu.cpp:276
static freenect_context * ctx
int libusb_submit_transfer(struct libusb_transfer *transfer)
Definition: libusbemu.cpp:529
FN_INTERNAL int fnusb_process_events_timeout(fnusb_ctx *ctx, struct timeval *timeout)
Definition: usb_libusb10.c:250
#define PID_K4W_AUDIO_ALT_1
int libusb_claim_interface(libusb_device_handle *dev, int interface_number)
Definition: libusbemu.cpp:316
#define FN_INTERNAL
unsigned int fn_fw_nui_size
int libusb_cancel_transfer(struct libusb_transfer *transfer)
Definition: libusbemu.cpp:578
freenect_device_flags
Definition: libfreenect.h:58
#define PID_NUI_CAMERA
FN_INTERNAL int fnusb_is_pid_k4w_audio(int pid)
Definition: usb_libusb10.c:64
FN_INTERNAL int fnusb_process_events(fnusb_ctx *ctx)
Definition: usb_libusb10.c:245
int libusb_bulk_transfer(libusb_device_handle *dev_handle, unsigned char endpoint, unsigned char *data, int length, int *actual_length, unsigned int timeout)
Definition: libusbemu.cpp:412
unsigned char endpoint
Definition: libusb.h:160
#define fn_le32(x)
static void LIBUSB_CALL iso_callback(struct libusb_transfer *xfer)
Definition: usb_libusb10.c:673
FN_INTERNAL int fnusb_init(fnusb_ctx *ctx, freenect_usb_context *usb_ctx)
Definition: usb_libusb10.c:214
FN_INTERNAL int fnusb_num_devices(fnusb_ctx *ctx)
Definition: usb_libusb10.c:40
int libusb_set_interface_alt_setting(libusb_device_handle *dev, int interface_number, int alternate_setting)
Definition: libusbemu.cpp:305
void libusb_exit(libusb_context *ctx)
Definition: libusbemu.cpp:110
libusb_context * ctx
Definition: usb_libusb10.h:64
struct libusb_transfer ** xfers
Definition: usb_libusb10.h:76


libfreenect
Author(s): Hector Martin, Josh Blake, Kyle Machulis, OpenKinect community
autogenerated on Thu Jun 6 2019 19:25:38