uvc-v4l2.cpp
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2015 Intel Corporation. All Rights Reserved.
3 
4 #ifdef RS_USE_V4L2_BACKEND
5 
6 #include "uvc.h"
7 
8 #include <cassert>
9 #include <cstdlib>
10 #include <cstdio>
11 #include <sstream>
12 #include <cstring>
13 
14 #include <algorithm>
15 #include <functional>
16 #include <string>
17 #include <sstream>
18 #include <fstream>
19 #include <regex>
20 #include <thread>
21 #include <utility> // for pair
22 #include <chrono>
23 #include <thread>
24 
25 #include <dirent.h>
26 #include <fcntl.h>
27 #include <unistd.h>
28 #include <limits.h>
29 #include <errno.h>
30 #include <sys/stat.h>
31 #include <sys/mman.h>
32 #include <sys/ioctl.h>
33 #include <sys/sysmacros.h>
34 #include <linux/usb/video.h>
35 #include <linux/uvcvideo.h>
36 #include <linux/videodev2.h>
37 
38 #pragma GCC diagnostic ignored "-Wpedantic"
39 #include <libusb.h>
40 #pragma GCC diagnostic pop
41 
42 #pragma GCC diagnostic ignored "-Woverflow"
43 
44 #ifndef V4L2_CAP_META_CAPTURE
45 #define V4L2_CAP_META_CAPTURE 0x00800000 /* Specified in kernel header v4.16, required for back-compat */
46 #endif // V4L2_CAP_META_CAPTURE
47 
48 namespace rsimpl
49 {
50  namespace uvc
51  {
52  static void throw_error(const char * s)
53  {
54  std::ostringstream ss;
55  ss << s << " error " << errno << ", " << strerror(errno);
56  throw std::runtime_error(ss.str());
57  }
58 
59  static void warn_error(const char * s)
60  {
61  LOG_ERROR(s << " error " << errno << ", " << strerror(errno));
62  }
63 
64  static int xioctl(int fh, int request, void *arg)
65  {
66  int r;
67  do {
68  r = ioctl(fh, request, arg);
69  } while (r < 0 && errno == EINTR);
70  return r;
71  }
72 
73  struct buffer { void * start; size_t length; };
74 
75  struct context
76  {
77  libusb_context * usb_context;
78 
79  context()
80  {
81  int status = libusb_init(&usb_context);
82  if(status < 0) throw std::runtime_error(to_string() << "libusb_init(...) returned " << libusb_error_name(status));
83  }
84  ~context()
85  {
86  libusb_exit(usb_context);
87  }
88  };
89 
90  struct subdevice
91  {
92  std::string dev_name; // Device name (typically of the form /dev/video*)
93  int busnum, devnum, parent_devnum; // USB device bus number and device number (needed for F200/SR300 direct USB controls)
94  int vid, pid, mi; // Vendor ID, product ID, and multiple interface index
95  int fd; // File descriptor for this device
96  std::vector<buffer> buffers;
97 
98  int width, height, format, fps;
99  video_channel_callback callback = nullptr;
100  data_channel_callback channel_data_callback = nullptr; // handle non-uvc data produced by device
101  bool is_capturing;
102  bool is_metastream;
103 
104  subdevice(const std::string & name) : dev_name("/dev/" + name), vid(), pid(), fd(), width(), height(), format(), callback(nullptr), channel_data_callback(nullptr), is_capturing(), is_metastream()
105  {
106  struct stat st;
107  if(stat(dev_name.c_str(), &st) < 0)
108  {
109  std::ostringstream ss; ss << "Cannot identify '" << dev_name << "': " << errno << ", " << strerror(errno);
110  throw std::runtime_error(ss.str());
111  }
112  if(!S_ISCHR(st.st_mode)) throw std::runtime_error(dev_name + " is no device");
113 
114  // Search directory and up to three parent directories to find busnum/devnum
115  std::ostringstream ss; ss << "/sys/dev/char/" << major(st.st_rdev) << ":" << minor(st.st_rdev) << "/device/";
116  auto path = ss.str();
117  bool good = false;
118  for(int i=0; i<=3; ++i)
119  {
120  if(std::ifstream(path + "busnum") >> busnum)
121  {
122  if(std::ifstream(path + "devnum") >> devnum)
123  {
124  if(std::ifstream(path + "../devnum") >> parent_devnum)
125  {
126  good = true;
127  break;
128  }
129  }
130  }
131  path += "../";
132  }
133  if(!good) throw std::runtime_error("Failed to read busnum/devnum");
134 
135  std::string modalias;
136  if(!(std::ifstream("/sys/class/video4linux/" + name + "/device/modalias") >> modalias))
137  throw std::runtime_error("Failed to read modalias");
138  if(modalias.size() < 14 || modalias.substr(0,5) != "usb:v" || modalias[9] != 'p')
139  throw std::runtime_error("Not a usb format modalias");
140  if(!(std::istringstream(modalias.substr(5,4)) >> std::hex >> vid))
141  throw std::runtime_error("Failed to read vendor ID");
142  if(!(std::istringstream(modalias.substr(10,4)) >> std::hex >> pid))
143  throw std::runtime_error("Failed to read product ID");
144  if(!(std::ifstream("/sys/class/video4linux/" + name + "/device/bInterfaceNumber") >> std::hex >> mi))
145  throw std::runtime_error("Failed to read interface number");
146 
147  fd = open(dev_name.c_str(), O_RDWR | O_NONBLOCK, 0);
148  if(fd < 0)
149  {
150  std::ostringstream ss; ss << "Cannot open '" << dev_name << "': " << errno << ", " << strerror(errno);
151  throw std::runtime_error(ss.str());
152  }
153 
154  v4l2_capability cap = {};
155  if(xioctl(fd, VIDIOC_QUERYCAP, &cap) < 0)
156  {
157  if(errno == EINVAL) throw std::runtime_error(dev_name + " is no V4L2 device");
158  else throw_error("VIDIOC_QUERYCAP");
159  }
160  if(!(cap.capabilities & V4L2_CAP_VIDEO_CAPTURE)) throw std::runtime_error(dev_name + " is no video capture device");
161  if(!(cap.capabilities & V4L2_CAP_STREAMING)) throw std::runtime_error(dev_name + " does not support streaming I/O");
162  if((cap.device_caps & V4L2_CAP_META_CAPTURE)){
163  is_metastream=true;
164  }
165 
166  // Select video input, video standard and tune here.
167  v4l2_cropcap cropcap = {};
168  cropcap.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
169  if(xioctl(fd, VIDIOC_CROPCAP, &cropcap) == 0)
170  {
171  v4l2_crop crop = {};
172  crop.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
173  crop.c = cropcap.defrect; // reset to default
174  if(xioctl(fd, VIDIOC_S_CROP, &crop) < 0)
175  {
176  switch (errno)
177  {
178  case EINVAL: break; // Cropping not supported
179  default: break; // Errors ignored
180  }
181  }
182  } else {} // Errors ignored
183  }
184 
185  ~subdevice()
186  {
187  stop_capture();
188  if(close(fd) < 0) warn_error("close");
189  }
190 
191  int get_vid() const { return vid; }
192  int get_pid() const { return pid; }
193  int get_mi() const { return mi; }
194 
195  void get_control(const extension_unit & xu, uint8_t control, void * data, size_t size)
196  {
197  uvc_xu_control_query q = {static_cast<uint8_t>(xu.unit), control, UVC_GET_CUR, static_cast<uint16_t>(size), reinterpret_cast<uint8_t *>(data)};
198  if(xioctl(fd, UVCIOC_CTRL_QUERY, &q) < 0) throw_error("UVCIOC_CTRL_QUERY:UVC_GET_CUR");
199  }
200 
201  void set_control(const extension_unit & xu, uint8_t control, void * data, size_t size)
202  {
203  uvc_xu_control_query q = {static_cast<uint8_t>(xu.unit), control, UVC_SET_CUR, static_cast<uint16_t>(size), reinterpret_cast<uint8_t *>(data)};
204  if(xioctl(fd, UVCIOC_CTRL_QUERY, &q) < 0) throw_error("UVCIOC_CTRL_QUERY:UVC_SET_CUR");
205  }
206 
207  void set_format(int width, int height, int fourcc, int fps, video_channel_callback callback)
208  {
209  this->width = width;
210  this->height = height;
211  this->format = fourcc;
212  this->fps = fps;
213  this->callback = callback;
214  }
215 
216  void set_data_channel_cfg(data_channel_callback callback)
217  {
218  this->channel_data_callback = callback;
219  }
220 
221  void start_capture()
222  {
223  if(!is_capturing)
224  {
225  v4l2_format fmt = {};
226  fmt.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
227  fmt.fmt.pix.width = width;
228  fmt.fmt.pix.height = height;
229  fmt.fmt.pix.pixelformat = format;
230  fmt.fmt.pix.field = V4L2_FIELD_NONE;
231  if(xioctl(fd, VIDIOC_S_FMT, &fmt) < 0) throw_error("VIDIOC_S_FMT");
232 
233  v4l2_streamparm parm = {};
234  parm.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
235  if(xioctl(fd, VIDIOC_G_PARM, &parm) < 0) throw_error("VIDIOC_G_PARM");
236  parm.parm.capture.timeperframe.numerator = 1;
237  parm.parm.capture.timeperframe.denominator = fps;
238  if(xioctl(fd, VIDIOC_S_PARM, &parm) < 0) throw_error("VIDIOC_S_PARM");
239 
240  // Init memory mapped IO
241  v4l2_requestbuffers req = {};
242  req.count = 4;
243  req.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
244  req.memory = V4L2_MEMORY_MMAP;
245  if(xioctl(fd, VIDIOC_REQBUFS, &req) < 0)
246  {
247  if(errno == EINVAL) throw std::runtime_error(dev_name + " does not support memory mapping");
248  else throw_error("VIDIOC_REQBUFS");
249  }
250  if(req.count < 2)
251  {
252  throw std::runtime_error("Insufficient buffer memory on " + dev_name);
253  }
254 
255  buffers.resize(req.count);
256  for(size_t i = 0; i < buffers.size(); ++i)
257  {
258  v4l2_buffer buf = {};
259  buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
260  buf.memory = V4L2_MEMORY_MMAP;
261  buf.index = i;
262  if(xioctl(fd, VIDIOC_QUERYBUF, &buf) < 0) throw_error("VIDIOC_QUERYBUF");
263 
264  buffers[i].length = buf.length;
265  buffers[i].start = mmap(NULL, buf.length, PROT_READ | PROT_WRITE, MAP_SHARED, fd, buf.m.offset);
266  if(buffers[i].start == MAP_FAILED) throw_error("mmap");
267  }
268 
269  // Start capturing
270  for(size_t i = 0; i < buffers.size(); ++i)
271  {
272  v4l2_buffer buf = {};
273  buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
274  buf.memory = V4L2_MEMORY_MMAP;
275  buf.index = i;
276  if(xioctl(fd, VIDIOC_QBUF, &buf) < 0) throw_error("VIDIOC_QBUF");
277  }
278 
279  v4l2_buf_type type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
280  for(int i=0; i<10; ++i)
281  {
282  if(xioctl(fd, VIDIOC_STREAMON, &type) < 0)
283  {
284  std::this_thread::sleep_for(std::chrono::milliseconds(100));
285  }
286  }
287  if(xioctl(fd, VIDIOC_STREAMON, &type) < 0) throw_error("VIDIOC_STREAMON");
288 
289  is_capturing = true;
290  }
291  }
292 
293  void stop_capture()
294  {
295  if(is_capturing)
296  {
297  // Stop streamining
298  v4l2_buf_type type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
299  if(xioctl(fd, VIDIOC_STREAMOFF, &type) < 0) warn_error("VIDIOC_STREAMOFF");
300 
301  for(size_t i = 0; i < buffers.size(); i++)
302  {
303  if(munmap(buffers[i].start, buffers[i].length) < 0) warn_error("munmap");
304  }
305 
306  // Close memory mapped IO
307  struct v4l2_requestbuffers req = {};
308  req.count = 0;
309  req.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
310  req.memory = V4L2_MEMORY_MMAP;
311  if(xioctl(fd, VIDIOC_REQBUFS, &req) < 0)
312  {
313  if(errno == EINVAL) LOG_ERROR(dev_name + " does not support memory mapping");
314  else warn_error("VIDIOC_REQBUFS");
315  }
316 
317  callback = nullptr;
318  is_capturing = false;
319  }
320  }
321 
322  static void poll(const std::vector<subdevice *> & subdevices)
323  {
324  int max_fd = 0;
325  fd_set fds;
326  FD_ZERO(&fds);
327  for(auto * sub : subdevices)
328  {
329  FD_SET(sub->fd, &fds);
330  max_fd = std::max(max_fd, sub->fd);
331  }
332 
333  struct timeval tv = {0,10000};
334  if(select(max_fd + 1, &fds, NULL, NULL, &tv) < 0)
335  {
336  if (errno == EINTR) return;
337  throw_error("select");
338  }
339 
340  for(auto * sub : subdevices)
341  {
342  if(FD_ISSET(sub->fd, &fds))
343  {
344  v4l2_buffer buf = {};
345  buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
346  buf.memory = V4L2_MEMORY_MMAP;
347  if(xioctl(sub->fd, VIDIOC_DQBUF, &buf) < 0)
348  {
349  if(errno == EAGAIN) return;
350  throw_error("VIDIOC_DQBUF");
351  }
352 
353  sub->callback(sub->buffers[buf.index].start,
354  [sub, buf]() mutable {
355  if(xioctl(sub->fd, VIDIOC_QBUF, &buf) < 0) throw_error("VIDIOC_QBUF");
356  });
357  }
358  }
359  }
360 
361  static void poll_interrupts(libusb_device_handle *handle, const std::vector<subdevice *> & subdevices, uint16_t timeout)
362  {
363  static const unsigned short interrupt_buf_size = 0x400;
364  uint8_t buffer[interrupt_buf_size]; /* 64 byte transfer buffer - dedicated channel*/
365  int num_bytes = 0; /* Actual bytes transferred. */
366 
367  // TODO - replace hard-coded values : 0x82 and 1000
368  int res = libusb_interrupt_transfer(handle, 0x84, buffer, interrupt_buf_size, &num_bytes, timeout);
369  if (0 == res)
370  {
371  // Propagate the data to device layer
372  for(auto & sub : subdevices)
373  if (sub->channel_data_callback)
374  sub->channel_data_callback(buffer, num_bytes);
375  }
376  else
377  {
378  switch (res)
379  {
380  case LIBUSB_ERROR_TIMEOUT :
381  LOG_WARNING("interrupt e.p. timeout");
382  break;
383  default:
384  throw std::runtime_error(to_string() << "USB Interrupt end-point error " << libusb_strerror((libusb_error)res));
385  break;
386  }
387  }
388  }
389  };
390 
391  struct device
392  {
393  const std::shared_ptr<context> parent;
394  std::vector<std::unique_ptr<subdevice>> subdevices;
395  std::thread thread;
396  std::thread data_channel_thread;
397  volatile bool stop;
398  volatile bool data_stop;
399 
400  libusb_device * usb_device;
401  libusb_device_handle * usb_handle;
402  std::vector<int> claimed_interfaces;
403 
404  device(std::shared_ptr<context> parent) : parent(parent), stop(), data_stop(), usb_device(), usb_handle() {}
405  ~device()
406  {
407  stop_streaming();
408 
409  for(auto interface_number : claimed_interfaces)
410  {
411  int status = libusb_release_interface(usb_handle, interface_number);
412  if(status < 0) LOG_ERROR("libusb_release_interface(...) returned " << libusb_error_name(status));
413  }
414 
415  if(usb_handle) libusb_close(usb_handle);
416  if(usb_device) libusb_unref_device(usb_device);
417  }
418 
419  bool has_mi(int mi) const
420  {
421  for(auto & sub : subdevices)
422  {
423  if(sub->get_mi() == mi) return true;
424  }
425  return false;
426  }
427 
428  void start_streaming()
429  {
430  std::vector<subdevice *> subs;
431 
432  for(auto & sub : subdevices)
433  {
434  if(sub->callback)
435  {
436  sub->start_capture();
437  subs.push_back(sub.get());
438  }
439  }
440 
441  thread = std::thread([this, subs]()
442  {
443  while(!stop) subdevice::poll(subs);
444  });
445  }
446 
447  void stop_streaming()
448  {
449  if(thread.joinable())
450  {
451  stop = true;
452  thread.join();
453  stop = false;
454 
455  for(auto & sub : subdevices) sub->stop_capture();
456  }
457  }
458 
460  {
461  std::vector<subdevice *> data_channel_subs;
462  for (auto & sub : subdevices)
463  {
464  if (sub->channel_data_callback)
465  {
466  data_channel_subs.push_back(sub.get());
467  }
468  }
469 
470  // Motion events polling pipe
471  if (claimed_interfaces.size())
472  {
473  data_channel_thread = std::thread([this, data_channel_subs]()
474  {
475  // Polling 100ms timeout
476  while (!data_stop)
477  {
478  subdevice::poll_interrupts(this->usb_handle, data_channel_subs, 100);
479  }
480  });
481  }
482  }
483 
484  void stop_data_acquisition()
485  {
486  if (data_channel_thread.joinable())
487  {
488  data_stop = true;
489  data_channel_thread.join();
490  data_stop = false;
491  }
492  }
493  };
494 
496  // device //
498 
499  int get_vendor_id(const device & device) { return device.subdevices[0]->get_vid(); }
500  int get_product_id(const device & device) { return device.subdevices[0]->get_pid(); }
501 
502  std::string get_usb_port_id(const device & device)
503  {
504  std::string usb_bus = std::to_string(libusb_get_bus_number(device.usb_device));
505 
506  // As per the USB 3.0 specs, the current maximum limit for the depth is 7.
507  const int max_usb_depth = 8;
508  uint8_t usb_ports[max_usb_depth];
509  std::stringstream port_path;
510  int port_count = libusb_get_port_numbers(device.usb_device, usb_ports, max_usb_depth);
511 
512  for (size_t i = 0; i < port_count; ++i)
513  {
514  port_path << "-" << std::to_string(usb_ports[i]);
515  }
516 
517  return usb_bus + port_path.str();
518  }
519 
520  void get_control(const device & device, const extension_unit & xu, uint8_t ctrl, void * data, int len)
521  {
522  device.subdevices[xu.subdevice]->get_control(xu, ctrl, data, len);
523  }
524  void set_control(device & device, const extension_unit & xu, uint8_t ctrl, void * data, int len)
525  {
526  device.subdevices[xu.subdevice]->set_control(xu, ctrl, data, len);
527  }
528 
529  void claim_interface(device & device, const guid & /*interface_guid*/, int interface_number)
530  {
531  if(!device.usb_handle)
532  {
533  int status = libusb_open(device.usb_device, &device.usb_handle);
534  if(status < 0) throw std::runtime_error(to_string() << "libusb_open(...) returned " << libusb_error_name(status));
535  }
536 
537  int status = libusb_claim_interface(device.usb_handle, interface_number);
538  if(status < 0) throw std::runtime_error(to_string() << "libusb_claim_interface(...) returned " << libusb_error_name(status));
539  device.claimed_interfaces.push_back(interface_number);
540  }
541  void claim_aux_interface(device & device, const guid & interface_guid, int interface_number)
542  {
543  claim_interface(device, interface_guid, interface_number);
544  }
545 
546  void bulk_transfer(device & device, unsigned char endpoint, void * data, int length, int *actual_length, unsigned int timeout)
547  {
548  if(!device.usb_handle) throw std::logic_error("called uvc::bulk_transfer before uvc::claim_interface");
549  int status = libusb_bulk_transfer(device.usb_handle, endpoint, (unsigned char *)data, length, actual_length, timeout);
550  if(status < 0) throw std::runtime_error(to_string() << "libusb_bulk_transfer(...) returned " << libusb_error_name(status));
551  }
552 
553  void interrupt_transfer(device & device, unsigned char endpoint, void * data, int length, int *actual_length, unsigned int timeout)
554  {
555  if(!device.usb_handle) throw std::logic_error("called uvc::interrupt_transfer before uvc::claim_interface");
556  int status = libusb_interrupt_transfer(device.usb_handle, endpoint, (unsigned char *)data, length, actual_length, timeout);
557  if(status < 0) throw std::runtime_error(to_string() << "libusb_interrupt_transfer(...) returned " << libusb_error_name(status));
558  }
559 
560  void set_subdevice_mode(device & device, int subdevice_index, int width, int height, uint32_t fourcc, int fps, video_channel_callback callback)
561  {
562  device.subdevices[subdevice_index]->set_format(width, height, (const big_endian<int> &)fourcc, fps, callback);
563  }
564 
565  void set_subdevice_data_channel_handler(device & device, int subdevice_index, data_channel_callback callback)
566  {
567  device.subdevices[subdevice_index]->set_data_channel_cfg(callback);
568  }
569 
570  void start_streaming(device & device, int /*num_transfer_bufs*/)
571  {
572  device.start_streaming();
573  }
574 
575  void stop_streaming(device & device)
576  {
577  device.stop_streaming();
578  }
579 
580  void start_data_acquisition(device & device)
581  {
582  device.start_data_acquisition();
583  }
584 
585  void stop_data_acquisition(device & device)
586  {
587  device.stop_data_acquisition();
588  }
589 
590  static uint32_t get_cid(rs_option option)
591  {
592  switch(option)
593  {
594  case RS_OPTION_COLOR_BACKLIGHT_COMPENSATION: return V4L2_CID_BACKLIGHT_COMPENSATION;
595  case RS_OPTION_COLOR_BRIGHTNESS: return V4L2_CID_BRIGHTNESS;
596  case RS_OPTION_COLOR_CONTRAST: return V4L2_CID_CONTRAST;
597  case RS_OPTION_COLOR_EXPOSURE: return V4L2_CID_EXPOSURE_ABSOLUTE; // Is this actually valid? I'm getting a lot of VIDIOC error 22s...
598  case RS_OPTION_COLOR_GAIN: return V4L2_CID_GAIN;
599  case RS_OPTION_COLOR_GAMMA: return V4L2_CID_GAMMA;
600  case RS_OPTION_COLOR_HUE: return V4L2_CID_HUE;
601  case RS_OPTION_COLOR_SATURATION: return V4L2_CID_SATURATION;
602  case RS_OPTION_COLOR_SHARPNESS: return V4L2_CID_SHARPNESS;
603  case RS_OPTION_COLOR_WHITE_BALANCE: return V4L2_CID_WHITE_BALANCE_TEMPERATURE;
604  case RS_OPTION_COLOR_ENABLE_AUTO_EXPOSURE: return V4L2_CID_EXPOSURE_AUTO; // Automatic gain/exposure control
605  case RS_OPTION_COLOR_ENABLE_AUTO_WHITE_BALANCE: return V4L2_CID_AUTO_WHITE_BALANCE;
606  case RS_OPTION_FISHEYE_GAIN: return V4L2_CID_GAIN;
607  default: throw std::runtime_error(to_string() << "no v4l2 cid for option " << option);
608  }
609  }
610 
611  void set_pu_control(device & device, int subdevice, rs_option option, int value)
612  {
613  struct v4l2_control control = {get_cid(option), value};
614  if (RS_OPTION_COLOR_ENABLE_AUTO_EXPOSURE==option) { control.value = value ? V4L2_EXPOSURE_APERTURE_PRIORITY : V4L2_EXPOSURE_MANUAL; }
615  if (xioctl(device.subdevices[subdevice]->fd, VIDIOC_S_CTRL, &control) < 0) throw_error("VIDIOC_S_CTRL");
616  }
617 
618  int get_pu_control(const device & device, int subdevice, rs_option option)
619  {
620  struct v4l2_control control = {get_cid(option), 0};
621  if (xioctl(device.subdevices[subdevice]->fd, VIDIOC_G_CTRL, &control) < 0) throw_error("VIDIOC_G_CTRL");
622  if (RS_OPTION_COLOR_ENABLE_AUTO_EXPOSURE==option) { control.value = (V4L2_EXPOSURE_MANUAL==control.value) ? 0 : 1; }
623  return control.value;
624  }
625 
626  void get_pu_control_range(const device & device, int subdevice, rs_option option, int * min, int * max, int * step, int * def)
627  {
628  // Auto controls range is trimed to {0,1} range
630  {
631  if(min) *min = 0;
632  if(max) *max = 1;
633  if(step) *step = 1;
634  if(def) *def = 1;
635  return;
636  }
637 
638  struct v4l2_queryctrl query = {};
639  query.id = get_cid(option);
640  if (xioctl(device.subdevices[subdevice]->fd, VIDIOC_QUERYCTRL, &query) < 0)
641  {
642  // Some controls (exposure, auto exposure, auto hue) do not seem to work on V4L2
643  // Instead of throwing an error, return an empty range. This will cause this control to be omitted on our UI sample.
644  // TODO: Figure out what can be done about these options and make this work
645  query.minimum = query.maximum = 0;
646  }
647  if(min) *min = query.minimum;
648  if(max) *max = query.maximum;
649  if(step) *step = query.step;
650  if(def) *def = query.default_value;
651  }
652 
653  void get_extension_control_range(const device & device, const extension_unit & xu, char control, int * min, int * max, int * step, int * def)
654  {
655  __u16 size = 0;
656  __u8 value = 0; /* all of the real sense extended controls are one byte,
657  checking return value for UVC_GET_LEN and allocating
658  appropriately might be better */
659  __u8 * data = (__u8 *)&value;
660  struct uvc_xu_control_query xquery;
661  memset(&xquery, 0, sizeof(xquery));
662  xquery.query = UVC_GET_LEN;
663  xquery.size = 2; /* size seems to always be 2 for the LEN query, but
664  doesn't seem to be documented. Use result for size
665  in all future queries of the same control number */
666  xquery.selector = control;
667  xquery.unit = xu.unit;
668  xquery.data = (__u8 *)&size;
669 
670  if(-1 == ioctl(device.subdevices[xu.subdevice]->fd,UVCIOC_CTRL_QUERY,&xquery)){
671  throw std::runtime_error(to_string() << " ioctl failed on UVC_GET_LEN");
672  }
673 
674  xquery.query = UVC_GET_MIN;
675  xquery.size = size;
676  xquery.selector = control;
677  xquery.unit = xu.unit;
678  xquery.data = data;
679  if(-1 == ioctl(device.subdevices[xu.subdevice]->fd,UVCIOC_CTRL_QUERY,&xquery)){
680  throw std::runtime_error(to_string() << " ioctl failed on UVC_GET_MIN");
681  }
682  *min = value;
683 
684  xquery.query = UVC_GET_MAX;
685  xquery.size = size;
686  xquery.selector = control;
687  xquery.unit = xu.unit;
688  xquery.data = data;
689  if(-1 == ioctl(device.subdevices[xu.subdevice]->fd,UVCIOC_CTRL_QUERY,&xquery)){
690  throw std::runtime_error(to_string() << " ioctl failed on UVC_GET_MAX");
691  }
692  *max = value;
693 
694  xquery.query = UVC_GET_DEF;
695  xquery.size = size;
696  xquery.selector = control;
697  xquery.unit = xu.unit;
698  xquery.data = data;
699  if(-1 == ioctl(device.subdevices[xu.subdevice]->fd,UVCIOC_CTRL_QUERY,&xquery)){
700  throw std::runtime_error(to_string() << " ioctl failed on UVC_GET_DEF");
701  }
702  *def = value;
703 
704  xquery.query = UVC_GET_RES;
705  xquery.size = size;
706  xquery.selector = control;
707  xquery.unit = xu.unit;
708  xquery.data = data;
709  if(-1 == ioctl(device.subdevices[xu.subdevice]->fd,UVCIOC_CTRL_QUERY,&xquery)){
710  throw std::runtime_error(to_string() << " ioctl failed on UVC_GET_CUR");
711  }
712  *step = value;
713 
714  }
716  // context //
718 
719  std::shared_ptr<context> create_context()
720  {
721  return std::make_shared<context>();
722  }
723 
724  bool is_device_connected(device & device, int vid, int pid)
725  {
726  for (auto& sub : device.subdevices)
727  {
728  if (sub->vid == vid && sub->pid == pid)
729  return true;
730  }
731 
732  return false;
733  }
734 
735  std::vector<std::shared_ptr<device>> query_devices(std::shared_ptr<context> context)
736  {
737  // Enumerate all subdevices present on the system
738  std::vector<std::unique_ptr<subdevice>> subdevices;
739  DIR * dir = opendir("/sys/class/video4linux");
740  if(!dir) throw std::runtime_error("Cannot access /sys/class/video4linux");
741  while (dirent * entry = readdir(dir))
742  {
743  std::string name = entry->d_name;
744  if(name == "." || name == "..") continue;
745 
746  // Resolve a pathname to ignore virtual video devices
747  std::string path = "/sys/class/video4linux/" + name;
748  char buff[PATH_MAX];
749  ssize_t len = ::readlink(path.c_str(), buff, sizeof(buff)-1);
750  if (len != -1)
751  {
752  buff[len] = '\0';
753  std::string real_path = std::string(buff);
754  if (real_path.find("virtual") != std::string::npos)
755  continue;
756  }
757 
758  try
759  {
760  std::unique_ptr<subdevice> sub(new subdevice(name));
761  subdevices.push_back(move(sub));
762  }
763  catch(const std::exception & e)
764  {
765  LOG_INFO("Not a USB video device: " << e.what());
766  }
767  }
768  closedir(dir);
769 
770  // Note: Subdevices of a given device may not be contiguous. We can test our grouping/sorting logic by calling random_shuffle.
771  // std::random_shuffle(begin(subdevices), end(subdevices));
772 
773  // Group subdevices by busnum/devnum
774  std::vector<std::shared_ptr<device>> devices;
775  for(auto & sub : subdevices)
776  {
777  bool is_new_device = true;
778  for(auto & dev : devices)
779  {
780  if(sub->busnum == dev->subdevices[0]->busnum && sub->devnum == dev->subdevices[0]->devnum)
781  {
782  if (sub->is_metastream) // avoid inserting metadata streamer
783  continue;
784  dev->subdevices.push_back(move(sub));
785  is_new_device = false;
786  break;
787  }
788  }
789  if(is_new_device)
790  {
791  if (sub->vid == VID_INTEL_CAMERA && sub->pid == ZR300_FISHEYE_PID) // avoid inserting fisheye camera as a device
792  continue;
793  if (sub->is_metastream) // avoid inserting metadata streamer
794  continue;
795  devices.push_back(std::make_shared<device>(context));
796  devices.back()->subdevices.push_back(move(sub));
797  }
798  }
799 
800  // Sort subdevices within each device by multiple-interface index
801  for(auto & dev : devices)
802  {
803  std::sort(begin(dev->subdevices), end(dev->subdevices), [](const std::unique_ptr<subdevice> & a, const std::unique_ptr<subdevice> & b)
804  {
805  return a->mi < b->mi;
806  });
807  }
808 
809 
810  // Insert fisheye camera as subDevice of ZR300
811  for(auto & sub : subdevices)
812  {
813  if (!sub)
814  continue;
815 
816  for(auto & dev : devices)
817  {
818  if (sub->is_metastream) // avoid inserting metadata streamer
819  continue;
820  if (dev->subdevices[0]->vid == VID_INTEL_CAMERA && dev->subdevices[0]->pid == ZR300_CX3_PID &&
821  sub->vid == VID_INTEL_CAMERA && sub->pid == ZR300_FISHEYE_PID && dev->subdevices[0]->parent_devnum == sub->parent_devnum)
822  {
823  dev->subdevices.push_back(move(sub));
824  break;
825  }
826  }
827  }
828 
829 
830  // Obtain libusb_device_handle for each device
831  libusb_device ** list;
832  int status = libusb_get_device_list(context->usb_context, &list);
833  if(status < 0) throw std::runtime_error(to_string() << "libusb_get_device_list(...) returned " << libusb_error_name(status));
834  for(int i=0; list[i]; ++i)
835  {
836  libusb_device * usb_device = list[i];
837  int busnum = libusb_get_bus_number(usb_device);
838  int devnum = libusb_get_device_address(usb_device);
839 
840  // Look for a video device whose busnum/devnum matches this USB device
841  for(auto & dev : devices)
842  {
843  if (dev->subdevices.size() >=4) // Make sure that four subdevices present
844  {
845  auto parent_device = libusb_get_parent(usb_device);
846  if (parent_device)
847  {
848  int parent_devnum = libusb_get_device_address(libusb_get_parent(usb_device));
849 
850  // First, handle the special case of FishEye
851  bool bFishEyeDevice = ((busnum == dev->subdevices[3]->busnum) && (parent_devnum == dev->subdevices[3]->parent_devnum));
852  if(bFishEyeDevice && !dev->usb_device)
853  {
854  dev->usb_device = usb_device;
855  libusb_ref_device(usb_device);
856  break;
857  }
858  }
859  }
860 
861  if(busnum == dev->subdevices[0]->busnum && devnum == dev->subdevices[0]->devnum)
862  {
863  if (!dev->usb_device) // do not override previous configuration
864  {
865  dev->usb_device = usb_device;
866  libusb_ref_device(usb_device);
867  break;
868  }
869  }
870  }
871  }
872  libusb_free_device_list(list, 1);
873 
874  return devices;
875  }
876  }
877 }
878 
879 #endif
std::shared_ptr< context > create_context()
void get_pu_control_range(const device &device, int subdevice, rs_option option, int *min, int *max, int *step, int *def)
void claim_aux_interface(device &device, const guid &interface_guid, int interface_number)
int major(int version)
Definition: rs.cpp:49
void set_subdevice_mode(device &device, int subdevice_index, int width, int height, uint32_t fourcc, int fps, video_channel_callback callback)
rs_error * e
GLint GLint GLsizei GLsizei height
Definition: glext.h:112
#define LOG_WARNING(...)
Definition: types.h:79
bool is_device_connected(device &device, int vid, int pid)
GLsizei const GLchar *const * path
Definition: glext.h:4034
const uint16_t VID_INTEL_CAMERA
Definition: uvc.h:14
GLsizei const GLchar *const * string
Definition: glext.h:683
GLenum GLuint GLenum GLsizei const GLchar * buf
Definition: glext.h:2479
const GLuint * buffers
Definition: glext.h:529
Definition: archive.h:12
rs_option
Defines general configuration controls.
Definition: rs.h:128
GLbitfield GLuint64 timeout
Definition: glext.h:1481
std::string get_usb_port_id(const device &device)
const uint16_t ZR300_FISHEYE_PID
Definition: uvc.h:16
GLuint buffer
Definition: glext.h:528
std::function< void(const unsigned char *data, const int size)> data_channel_callback
Definition: uvc.h:57
GLenum cap
Definition: glext.h:8336
GLenum GLsizei len
Definition: glext.h:3213
void set_subdevice_data_channel_handler(device &device, int subdevice_index, data_channel_callback callback)
void start_streaming(device &device, int num_transfer_bufs)
void start_data_acquisition(device &device)
void get_extension_control_range(const device &device, const extension_unit &xu, char control, int *min, int *max, int *step, int *def)
GLuint GLuint end
Definition: glext.h:111
format
Formats: defines how each stream can be encoded. rs_format specifies how a frame is represented in me...
Definition: rs.hpp:42
GLint GLenum GLsizei GLsizei GLsizei GLint GLsizei const void * data
Definition: glext.h:223
void stop_streaming(device &device)
GLboolean GLboolean GLboolean GLboolean a
Definition: glext.h:1104
GLsizei const GLfloat * value
Definition: glext.h:693
const uint16_t ZR300_CX3_PID
Definition: uvc.h:15
GLboolean GLboolean GLboolean b
Definition: glext.h:1104
#define LOG_INFO(...)
Definition: types.h:78
void claim_interface(device &device, const guid &interface_guid, int interface_number)
int get_pu_control(const device &device, int subdevice, rs_option option)
int get_product_id(const device &device)
void bulk_transfer(device &device, unsigned char endpoint, void *data, int length, int *actual_length, unsigned int timeout)
GLdouble s
Definition: glext.h:231
GLint GLint GLsizei width
Definition: glext.h:112
GLuint const GLchar * name
Definition: glext.h:655
void set_control(device &device, const extension_unit &xu, uint8_t ctrl, void *data, int len)
rs_device * dev
GLsizeiptr size
Definition: glext.h:532
int minor(int version)
Definition: rs.cpp:53
std::vector< std::shared_ptr< device > > query_devices(std::shared_ptr< context > context)
GLuint GLsizei GLsizei * length
Definition: glext.h:664
void set_pu_control(device &device, int subdevice, rs_option option, int value)
GLdouble GLdouble GLdouble GLdouble q
Definition: glext.h:255
GLuint res
Definition: glext.h:8310
void get_control(const device &device, const extension_unit &xu, uint8_t ctrl, void *data, int len)
void stop_data_acquisition(device &device)
GLdouble GLdouble GLdouble r
Definition: glext.h:247
GLenum query
Definition: glext.h:2708
GLuint start
Definition: glext.h:111
std::function< void(const void *frame, std::function< void()> continuation)> video_channel_callback
Definition: uvc.h:64
#define LOG_ERROR(...)
Definition: types.h:80
int get_vendor_id(const device &device)
GLuint GLuint GLsizei GLenum type
Definition: glext.h:111


librealsense
Author(s): Sergey Dorodnicov , Mark Horn , Reagan Lopez
autogenerated on Fri Mar 13 2020 03:16:18