backend-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 #include "backend-v4l2.h"
5 #include "backend-hid.h"
6 #include "backend.h"
7 #include "types.h"
8 #include "usb/usb-enumerator.h"
9 #include "usb/usb-device.h"
10 
11 #include <cassert>
12 #include <cstdlib>
13 #include <cstdio>
14 #include <cstring>
15 
16 #include <algorithm>
17 #include <functional>
18 #include <string>
19 #include <sstream>
20 #include <fstream>
21 #include <regex>
22 #include <thread>
23 #include <utility> // for pair
24 #include <chrono>
25 #include <thread>
26 #include <atomic>
27 #include <iomanip> // std::put_time
28 
29 #include <dirent.h>
30 #include <fcntl.h>
31 #include <unistd.h>
32 #include <limits.h>
33 #include <cmath>
34 #include <errno.h>
35 #include <sys/stat.h>
36 #include <sys/mman.h>
37 #include <sys/ioctl.h>
38 #include <sys/sysmacros.h> // minor(...), major(...)
39 #include <linux/usb/video.h>
40 #include <linux/uvcvideo.h>
41 #include <linux/videodev2.h>
42 #include <regex>
43 #include <list>
44 
45 #include <sys/signalfd.h>
46 #include <signal.h>
47 #pragma GCC diagnostic ignored "-Woverflow"
48 
49 const size_t MAX_DEV_PARENT_DIR = 10;
50 
51 #include "../tm2/tm-boot.h"
52 
53 #ifdef ANDROID
54 
55 // https://android.googlesource.com/platform/bionic/+/master/libc/include/bits/lockf.h
56 #define F_ULOCK 0
57 #define F_LOCK 1
58 #define F_TLOCK 2
59 #define F_TEST 3
60 
61 // https://android.googlesource.com/platform/bionic/+/master/libc/bionic/lockf.cpp
62 int lockf64(int fd, int cmd, off64_t length)
63 {
64  // Translate POSIX lockf into fcntl.
65  struct flock64 fl;
66  memset(&fl, 0, sizeof(fl));
67  fl.l_whence = SEEK_CUR;
68  fl.l_start = 0;
69  fl.l_len = length;
70 
71  if (cmd == F_ULOCK) {
72  fl.l_type = F_UNLCK;
73  cmd = F_SETLK64;
74  return fcntl(fd, F_SETLK64, &fl);
75  }
76 
77  if (cmd == F_LOCK) {
78  fl.l_type = F_WRLCK;
79  return fcntl(fd, F_SETLKW64, &fl);
80  }
81 
82  if (cmd == F_TLOCK) {
83  fl.l_type = F_WRLCK;
84  return fcntl(fd, F_SETLK64, &fl);
85  }
86  if (cmd == F_TEST) {
87  fl.l_type = F_RDLCK;
88  if (fcntl(fd, F_GETLK64, &fl) == -1) return -1;
89  if (fl.l_type == F_UNLCK || fl.l_pid == getpid()) return 0;
90  errno = EACCES;
91  return -1;
92  }
93 
94  errno = EINVAL;
95  return -1;
96 }
97 
98 int lockf(int fd, int cmd, off_t length)
99 {
100  return lockf64(fd, cmd, length);
101 }
102 #endif
103 
104 namespace librealsense
105 {
106  namespace platform
107  {
108  std::recursive_mutex named_mutex::_init_mutex;
109  std::map<std::string, std::recursive_mutex> named_mutex::_dev_mutex;
110  std::map<std::string, int> named_mutex::_dev_mutex_cnt;
111 
112  named_mutex::named_mutex(const std::string& device_path, unsigned timeout)
113  : _device_path(device_path),
114  _timeout(timeout), // TODO: try to lock with timeout
115  _fildes(-1),
116  _object_lock_counter(0)
117  {
118  _init_mutex.lock();
119  _dev_mutex[_device_path]; // insert a mutex for _device_path
120  if (_dev_mutex_cnt.find(_device_path) == _dev_mutex_cnt.end())
121  {
123  }
124  _init_mutex.unlock();
125  }
126 
128  {
129  unlock();
130  }
131 
133  {
134  std::lock_guard<std::mutex> lock(_mutex);
135  acquire();
136  }
137 
139  {
140  std::lock_guard<std::mutex> lock(_mutex);
141  release();
142  }
143 
145  {
146  std::lock_guard<std::mutex> lock(_mutex);
147  if (-1 == _fildes)
148  {
149  _fildes = open(_device_path.c_str(), O_RDWR, 0); //TODO: check
150  if(_fildes < 0)
151  return false;
152  }
153 
154  auto ret = lockf(_fildes, F_TLOCK, 0);
155  if (ret != 0)
156  return false;
157 
158  return true;
159  }
160 
162  {
163  _dev_mutex[_device_path].lock();
164  _dev_mutex_cnt[_device_path] += 1; //Advance counters even if throws because catch calls release()
166  if (_dev_mutex_cnt[_device_path] == 1)
167  {
168  if (-1 == _fildes)
169  {
170  _fildes = open(_device_path.c_str(), O_RDWR, 0); //TODO: check
171  if(0 > _fildes)
172  {
173  release();
174  throw linux_backend_exception(to_string() << __FUNCTION__ << ": Cannot open '" << _device_path);
175  }
176  }
177 
178  auto ret = lockf(_fildes, F_LOCK, 0);
179  if (0 != ret)
180  {
181  release();
182  throw linux_backend_exception(to_string() << __FUNCTION__ << ": Acquire failed");
183  }
184  }
185  }
186 
188  {
190  if (_object_lock_counter < 0)
191  {
193  return;
194  }
196  std::string err_msg;
197  if (_dev_mutex_cnt[_device_path] < 0)
198  {
200  throw linux_backend_exception(to_string() << "Error: _dev_mutex_cnt[" << _device_path << "] < 0");
201  }
202 
203  if ((_dev_mutex_cnt[_device_path] == 0) && (-1 != _fildes))
204  {
205  auto ret = lockf(_fildes, F_ULOCK, 0);
206  if (0 != ret)
207  err_msg = to_string() << "lockf(...) failed";
208  else
209  {
210  ret = close(_fildes);
211  if (0 != ret)
212  err_msg = to_string() << "close(...) failed";
213  else
214  _fildes = -1;
215  }
216  }
217  _dev_mutex[_device_path].unlock();
218 
219  if (!err_msg.empty())
220  throw linux_backend_exception(err_msg);
221 
222  }
223 
224  static int xioctl(int fh, unsigned long request, void *arg)
225  {
226  int r=0;
227  do {
228  r = ioctl(fh, request, arg);
229  } while (r < 0 && errno == EINTR);
230  return r;
231  }
232 
233  buffer::buffer(int fd, v4l2_buf_type type, bool use_memory_map, uint32_t index)
234  : _type(type), _use_memory_map(use_memory_map), _index(index)
235  {
236  v4l2_buffer buf = {};
237  buf.type = _type;
238  buf.memory = use_memory_map ? V4L2_MEMORY_MMAP : V4L2_MEMORY_USERPTR;
239  buf.index = index;
240  if(xioctl(fd, VIDIOC_QUERYBUF, &buf) < 0)
241  throw linux_backend_exception("xioctl(VIDIOC_QUERYBUF) failed");
242 
243  // Prior to kernel 4.16 metadata payload was attached to the end of the video payload
244  uint8_t md_extra = (V4L2_BUF_TYPE_VIDEO_CAPTURE==type) ? MAX_META_DATA_SIZE : 0;
245  _original_length = buf.length;
246  _length = _original_length + md_extra;
247 
248  if (use_memory_map)
249  {
250  _start = static_cast<uint8_t*>(mmap(nullptr, buf.length,
251  PROT_READ | PROT_WRITE, MAP_SHARED,
252  fd, buf.m.offset));
253  if(_start == MAP_FAILED)
254  throw linux_backend_exception("mmap failed");
255  }
256  else
257  {
258  //_length += (V4L2_BUF_TYPE_VIDEO_CAPTURE==type) ? MAX_META_DATA_SIZE : 0;
259  _start = static_cast<uint8_t*>(malloc( _length));
260  if (!_start) throw linux_backend_exception("User_p allocation failed!");
261  memset(_start, 0, _length);
262  }
263  }
264 
266  {
267  v4l2_buffer buf = {};
268  buf.type = _type;
269  buf.memory = _use_memory_map ? V4L2_MEMORY_MMAP : V4L2_MEMORY_USERPTR;
270  buf.index = _index;
271  buf.length = _length;
272 
273  if ( !_use_memory_map )
274  {
275  buf.m.userptr = reinterpret_cast<unsigned long>(_start);
276  }
277  if(xioctl(fd, VIDIOC_QBUF, &buf) < 0)
278  throw linux_backend_exception("xioctl(VIDIOC_QBUF) failed");
279  else
280  LOG_DEBUG_V4L("prepare_for_streaming fd " << std::dec << fd);
281  }
282 
284  {
285  if (_use_memory_map)
286  {
287  if(munmap(_start, _length) < 0)
288  linux_backend_exception("munmap");
289  }
290  else
291  {
292  free(_start);
293  }
294  }
295 
296  void buffer::attach_buffer(const v4l2_buffer& buf)
297  {
298  std::lock_guard<std::mutex> lock(_mutex);
299  _buf = buf;
300  _must_enqueue = true;
301  }
302 
304  {
305  std::lock_guard<std::mutex> lock(_mutex);
306  _must_enqueue = false;
307  }
308 
309  void buffer::request_next_frame(int fd, bool force)
310  {
311  std::lock_guard<std::mutex> lock(_mutex);
312 
313  if (_must_enqueue || force)
314  {
315  if (!_use_memory_map)
316  {
317  auto metadata_offset = get_full_length() - MAX_META_DATA_SIZE;
318  memset((byte*)(get_frame_start()) + metadata_offset, 0, MAX_META_DATA_SIZE);
319  }
320 
321  LOG_DEBUG_V4L("Enqueue buf " << std::dec << _buf.index << " for fd " << fd);
322  if (xioctl(fd, VIDIOC_QBUF, &_buf) < 0)
323  {
324  LOG_ERROR("xioctl(VIDIOC_QBUF) failed when requesting new frame! fd: " << fd << " error: " << strerror(errno));
325  }
326 
327  _must_enqueue = false;
328  }
329  }
330 
332  int file_desc,
333  v4l2_buffer v4l_buf,
334  std::shared_ptr<platform::buffer> data_buf
335  )
336  {
337  if (e_max_kernel_buf_type <=buf_type)
338  throw linux_backend_exception("invalid kernel buffer type request");
339 
340  if (file_desc < 1)
341  {
342  // QBUF to be performed by a 3rd party
343  this->buffers.at(buf_type)._managed = true;
344  }
345  else
346  {
347  buffers.at(buf_type)._file_desc = file_desc;
348  buffers.at(buf_type)._managed = false;
349  buffers.at(buf_type)._data_buf = data_buf;
350  buffers.at(buf_type)._dq_buf = v4l_buf;
351  }
352  }
353 
355  {
356  for (auto& buf : buffers)
357  {
358  if (buf._data_buf && (buf._file_desc >= 0))
359  buf._data_buf->request_next_frame(buf._file_desc);
360  };
361  _md_start = nullptr;
362  _md_size = 0;
363  }
364 
366  {
367  void* md_start = nullptr;
368  auto md_size = 0;
369 
370  if (buffers.at(e_video_buf)._file_desc >=0)
371  {
372  static const int d4xx_md_size = 248;
373  auto buffer = buffers.at(e_video_buf)._data_buf;
374  auto dq = buffers.at(e_video_buf)._dq_buf;
375  auto fr_payload_size = buffer->get_length_frame_only();
376 
377  // For compressed data assume D4XX metadata struct
378  // TODO - devise SKU-agnostic heuristics
379  auto md_appendix_sz = 0L;
380  if (compressed && (dq.bytesused < fr_payload_size))
381  md_appendix_sz = d4xx_md_size;
382  else
383  md_appendix_sz = long(dq.bytesused) - fr_payload_size;
384 
385  if (md_appendix_sz >0 )
386  {
387  md_start = buffer->get_frame_start() + dq.bytesused - md_appendix_sz;
388  md_size = (*(static_cast<uint8_t*>(md_start)));
389  int md_flags = (*(static_cast<uint8_t*>(md_start)+1));
390  // Use heuristics for metadata validation
391  if ((md_appendix_sz != md_size) || (!val_in_range(md_flags, {0x8e, 0x8f})))
392  {
393  md_size = 0;
394  md_start=nullptr;
395  }
396  }
397  }
398 
399  if (nullptr == md_start)
400  {
401  LOG_DEBUG("Could not parse metadata");
402  }
403  set_md_attributes(static_cast<uint8_t>(md_size),md_start);
404  }
405 
407  {
408  if ((buffers[e_video_buf]._file_desc > 0) && (buffers[e_metadata_buf]._file_desc > 0))
409  if (buffers[e_video_buf]._dq_buf.sequence != buffers[e_metadata_buf]._dq_buf.sequence)
410  {
411  LOG_ERROR("Non-sequential Video and Metadata v4l buffers");
412  return false;
413  }
414  return true;
415  }
416 
418  {
419  return (buffers[e_metadata_buf]._file_desc > 0);
420  }
421 
422  // retrieve the USB specification attributed to a specific USB device.
423  // This functionality is required to find the USB connection type for UVC device
424  // Note that the input parameter is passed by value
426  {
428 
429  char usb_actual_path[PATH_MAX] = {0};
430  if (realpath(path.c_str(), usb_actual_path) != nullptr)
431  {
432  path = std::string(usb_actual_path);
434  if(!(std::ifstream(path + "/version") >> val))
435  throw linux_backend_exception("Failed to read usb version specification");
436 
437  auto kvp = std::find_if(usb_spec_names.begin(),usb_spec_names.end(),
438  [&val](const std::pair<usb_spec, std::string>& kpv){ return (std::string::npos !=val.find(kpv.second));});
439  if (kvp != std::end(usb_spec_names))
440  res = kvp->first;
441  }
442  return res;
443  }
444 
445  // Retrieve device video capabilities to discriminate video capturing and metadata nodes
447  {
448  // RAII to handle exceptions
449  std::unique_ptr<int, std::function<void(int*)> > fd(
450  new int (open(dev_name.c_str(), O_RDWR | O_NONBLOCK, 0)),
451  [](int* d){ if (d && (*d)) {::close(*d); } delete d; });
452 
453  if(*fd < 0)
454  throw linux_backend_exception(to_string() << __FUNCTION__ << ": Cannot open '" << dev_name);
455 
456  v4l2_capability cap = {};
457  if(xioctl(*fd, VIDIOC_QUERYCAP, &cap) < 0)
458  {
459  if(errno == EINVAL)
460  throw linux_backend_exception(to_string() << __FUNCTION__ << " " << dev_name << " is no V4L2 device");
461  else
462  throw linux_backend_exception(to_string() <<__FUNCTION__ << " xioctl(VIDIOC_QUERYCAP) failed");
463  }
464 
465  return cap.device_caps;
466  }
467 
468  void stream_ctl_on(int fd, v4l2_buf_type type=V4L2_BUF_TYPE_VIDEO_CAPTURE)
469  {
470  if(xioctl(fd, VIDIOC_STREAMON, &type) < 0)
471  throw linux_backend_exception(to_string() << "xioctl(VIDIOC_STREAMON) failed for buf_type=" << type);
472  }
473 
474  void stream_off(int fd, v4l2_buf_type type=V4L2_BUF_TYPE_VIDEO_CAPTURE)
475  {
476  if(xioctl(fd, VIDIOC_STREAMOFF, &type) < 0)
477  throw linux_backend_exception(to_string() << "xioctl(VIDIOC_STREAMOFF) failed for buf_type=" << type);
478  }
479 
480  void req_io_buff(int fd, uint32_t count, std::string dev_name,
481  v4l2_memory mem_type, v4l2_buf_type type)
482  {
483  struct v4l2_requestbuffers req = { count, type, mem_type, {}};
484 
485  if(xioctl(fd, VIDIOC_REQBUFS, &req) < 0)
486  {
487  if(errno == EINVAL)
488  LOG_ERROR(dev_name + " does not support memory mapping");
489  else
490  throw linux_backend_exception("xioctl(VIDIOC_REQBUFS) failed");
491  }
492  }
493 
495  std::function<void(const uvc_device_info&,
496  const std::string&)> action)
497  {
498  // Enumerate all subdevices present on the system
499  DIR * dir = opendir("/sys/class/video4linux");
500  if(!dir)
501  {
502  LOG_INFO("Cannot access /sys/class/video4linux");
503  return;
504  }
505 
506  // Collect UVC nodes info to bundle metadata and video
507  typedef std::pair<uvc_device_info,std::string> node_info;
508  std::vector<node_info> uvc_nodes,uvc_devices;
509 
510  while (dirent * entry = readdir(dir))
511  {
512  std::string name = entry->d_name;
513  if(name == "." || name == "..") continue;
514 
515  // Resolve a pathname to ignore virtual video devices
516  std::string path = "/sys/class/video4linux/" + name;
517  std::string real_path{};
518  char buff[PATH_MAX] = {0};
519  if (realpath(path.c_str(), buff) != nullptr)
520  {
521  real_path = std::string(buff);
522  if (real_path.find("virtual") != std::string::npos)
523  continue;
524  }
525 
526  try
527  {
528  uint16_t vid, pid, mi;
529  std::string busnum, devnum, devpath;
530 
531  auto dev_name = "/dev/" + name;
532 
533  struct stat st = {};
534  if(stat(dev_name.c_str(), &st) < 0)
535  {
536  throw linux_backend_exception(to_string() << "Cannot identify '" << dev_name);
537  }
538  if(!S_ISCHR(st.st_mode))
539  throw linux_backend_exception(dev_name + " is no device");
540 
541  // Search directory and up to three parent directories to find busnum/devnum
542  std::ostringstream ss; ss << "/sys/dev/char/" << major(st.st_rdev) << ":" << minor(st.st_rdev) << "/device/";
543  auto path = ss.str();
544  auto valid_path = false;
545  for(auto i=0U; i < MAX_DEV_PARENT_DIR; ++i)
546  {
547  if(std::ifstream(path + "busnum") >> busnum)
548  {
549  if(std::ifstream(path + "devnum") >> devnum)
550  {
551  if(std::ifstream(path + "devpath") >> devpath)
552  {
553  valid_path = true;
554  break;
555  }
556  }
557  }
558  path += "../";
559  }
560  if(!valid_path)
561  {
562 #ifndef RS2_USE_CUDA
563  /* On the Jetson TX, the camera module is CSI & I2C and does not report as this code expects
564  Patch suggested by JetsonHacks: https://github.com/jetsonhacks/buildLibrealsense2TX */
565  LOG_INFO("Failed to read busnum/devnum. Device Path: " << path);
566 #endif
567  continue;
568  }
569 
570  std::string modalias;
571  if(!(std::ifstream("/sys/class/video4linux/" + name + "/device/modalias") >> modalias))
572  throw linux_backend_exception("Failed to read modalias");
573  if(modalias.size() < 14 || modalias.substr(0,5) != "usb:v" || modalias[9] != 'p')
574  throw linux_backend_exception("Not a usb format modalias");
575  if(!(std::istringstream(modalias.substr(5,4)) >> std::hex >> vid))
576  throw linux_backend_exception("Failed to read vendor ID");
577  if(!(std::istringstream(modalias.substr(10,4)) >> std::hex >> pid))
578  throw linux_backend_exception("Failed to read product ID");
579  if(!(std::ifstream("/sys/class/video4linux/" + name + "/device/bInterfaceNumber") >> std::hex >> mi))
580  throw linux_backend_exception("Failed to read interface number");
581 
582  // Find the USB specification (USB2/3) type from the underlying device
583  // Use device mapping obtained in previous step to traverse node tree
584  // and extract the required descriptors
585  // Traverse from
586  // /sys/devices/pci0000:00/0000:00:xx.0/ABC/M-N/3-6:1.0/video4linux/video0
587  // to
588  // /sys/devices/pci0000:00/0000:00:xx.0/ABC/M-N/version
589  usb_spec usb_specification = get_usb_connection_type(real_path + "/../../../");
590 
592  info.pid = pid;
593  info.vid = vid;
594  info.mi = mi;
595  info.id = dev_name;
596  info.device_path = std::string(buff);
597  info.unique_id = busnum + "-" + devpath + "-" + devnum;
598  info.conn_spec = usb_specification;
599  info.uvc_capabilities = get_dev_capabilities(dev_name);
600 
601  uvc_nodes.emplace_back(info, dev_name);
602  }
603  catch(const std::exception & e)
604  {
605  LOG_INFO("Not a USB video device: " << e.what());
606  }
607  }
608  closedir(dir);
609 
610  // Matching video and metadata nodes
611  // UVC nodes shall be traversed in ascending order for metadata nodes assignment ("dev/video1, Video2..
612  // Replace lexicographic with numeric sort to ensure "video2" is listed before "video11"
613  std::sort(begin(uvc_nodes),end(uvc_nodes),[](const node_info& lhs, const node_info& rhs)
614  {
615  std::stringstream index_l(lhs.first.id.substr(lhs.first.id.find_first_of("0123456789")));
616  std::stringstream index_r(rhs.first.id.substr(rhs.first.id.find_first_of("0123456789")));
617  int left_id = 0; index_l >> left_id;
618  int right_id = 0; index_r >> right_id;
619  return left_id < right_id;
620  });
621 
622  // Assume for each metadata node with index N there is a origin streaming node with index (N-1)
623  for (auto&& cur_node : uvc_nodes)
624  {
625  try
626  {
627  if (!(cur_node.first.uvc_capabilities & V4L2_CAP_META_CAPTURE))
628  uvc_devices.emplace_back(cur_node);
629  else
630  {
631  if (uvc_devices.empty())
632  {
633  LOG_ERROR("uvc meta-node with no video streaming node encountered: " << std::string(cur_node.first));
634  continue;
635  }
636 
637  // Update the preceding uvc item with metadata node info
638  auto uvc_node = uvc_devices.back();
639 
640  if (uvc_node.first.uvc_capabilities & V4L2_CAP_META_CAPTURE)
641  {
642  LOG_ERROR("Consequtive uvc meta-nodes encountered: " << std::string(uvc_node.first) << " and " << std::string(cur_node.first) );
643  continue;
644  }
645 
646  if (uvc_node.first.has_metadata_node)
647  {
648  LOG_ERROR( "Metadata node for uvc device: " << std::string(uvc_node.first) << " was previously assigned ");
649  continue;
650  }
651 
652  // modify the last element with metadata node info
653  uvc_node.first.has_metadata_node = true;
654  uvc_node.first.metadata_node_id = cur_node.first.id;
655  uvc_devices.back() = uvc_node;
656  }
657  }
658  catch(const std::exception & e)
659  {
660  LOG_ERROR("Failed to map meta-node " << std::string(cur_node.first) <<", error encountered: " << e.what());
661  }
662  }
663 
664  try
665  {
666  // Dispatch registration for enumerated uvc devices
667  for (auto&& dev : uvc_devices)
668  action(dev.first, dev.second);
669  }
670  catch(const std::exception & e)
671  {
672  LOG_ERROR("Registration of UVC device failed: " << e.what());
673  }
674  }
675 
677  : _name(""), _info(),
678  _is_capturing(false),
679  _is_alive(true),
680  _is_started(false),
681  _thread(nullptr),
682  _named_mtx(nullptr),
683  _use_memory_map(use_memory_map),
684  _fd(-1),
685  _stop_pipe_fd{},
686  _buf_dispatch(use_memory_map)
687  {
688  foreach_uvc_device([&info, this](const uvc_device_info& i, const std::string& name)
689  {
690  if (i == info)
691  {
692  _name = name;
693  _info = i;
696  }
697  });
698  if (_name == "")
699  throw linux_backend_exception("device is no longer connected!");
700 
701  _named_mtx = std::unique_ptr<named_mutex>(new named_mutex(_name, 5000));
702  }
703 
705  {
706  _is_capturing = false;
707  if (_thread && _thread->joinable()) _thread->join();
708  for (auto&& fd : _fds)
709  {
710  try { if (fd) ::close(fd);} catch (...) {}
711  }
712  }
713 
715  {
716  if(!_is_capturing && !_callback)
717  {
718  v4l2_fmtdesc pixel_format = {};
719  pixel_format.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
720 
721  while (ioctl(_fd, VIDIOC_ENUM_FMT, &pixel_format) == 0)
722  {
723  v4l2_frmsizeenum frame_size = {};
724  frame_size.pixel_format = pixel_format.pixelformat;
725 
726  uint32_t fourcc = (const big_endian<int> &)pixel_format.pixelformat;
727 
728  if (pixel_format.pixelformat == 0)
729  {
730  // Microsoft Depth GUIDs for R400 series are not yet recognized
731  // by the Linux kernel, but they do not require a patch, since there
732  // are "backup" Z16 and Y8 formats in place
733  static const std::set<std::string> pending_formats = {
734  "00000050-0000-0010-8000-00aa003",
735  "00000032-0000-0010-8000-00aa003",
736  };
737 
738  if (std::find(pending_formats.begin(),
739  pending_formats.end(),
740  (const char*)pixel_format.description) ==
741  pending_formats.end())
742  {
743  const std::string s(to_string() << "!" << pixel_format.description);
744  std::regex rgx("!([0-9a-f]+)-.*");
745  std::smatch match;
746 
747  if (std::regex_search(s.begin(), s.end(), match, rgx))
748  {
749  std::stringstream ss;
750  ss << match[1];
751  int id;
752  ss >> std::hex >> id;
753  fourcc = (const big_endian<int> &)id;
754 
755  if (fourcc == profile.format)
756  {
757  throw linux_backend_exception(to_string() << "The requested pixel format '" << fourcc_to_string(id)
758  << "' is not natively supported by the running Linux kernel and likely requires a patch");
759  }
760  }
761  }
762  }
763  ++pixel_format.index;
764  }
765 
766  set_format(profile);
767 
768  v4l2_streamparm parm = {};
769  parm.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
770  if(xioctl(_fd, VIDIOC_G_PARM, &parm) < 0)
771  throw linux_backend_exception("xioctl(VIDIOC_G_PARM) failed");
772 
773  parm.parm.capture.timeperframe.numerator = 1;
774  parm.parm.capture.timeperframe.denominator = profile.fps;
775  if(xioctl(_fd, VIDIOC_S_PARM, &parm) < 0)
776  throw linux_backend_exception("xioctl(VIDIOC_S_PARM) failed");
777 
778  // Init memory mapped IO
779  negotiate_kernel_buffers(static_cast<size_t>(buffers));
780  allocate_io_buffers(static_cast<size_t>(buffers));
781 
782  _profile = profile;
784  }
785  else
786  {
787  throw wrong_api_call_sequence_exception("Device already streaming!");
788  }
789  }
790 
791  void v4l_uvc_device::stream_on(std::function<void(const notification& n)> error_handler)
792  {
793  if(!_is_capturing)
794  {
795  _error_handler = error_handler;
796 
797  // Start capturing
799 
800  // Synchronise stream requests for meta and video data.
801  streamon();
802 
803  _is_capturing = true;
804  _thread = std::unique_ptr<std::thread>(new std::thread([this](){ capture_loop(); }));
805  }
806  }
807 
809  {
810  for (auto&& buf : _buffers) buf->prepare_for_streaming(_fd);
811  }
812 
814  {
815  _is_capturing = false;
816  _is_started = false;
817 
818  // Stop nn-demand frames polling
819  signal_stop();
820 
821  _thread->join();
822  _thread.reset();
823 
824  // Notify kernel
825  streamoff();
826  }
827 
829  {
830  _is_started = true;
831  }
832 
834  {
835  _is_started = false;
836  }
837 
839  {
840  if(_is_capturing)
841  {
843  }
844 
845  if (_callback)
846  {
847  // Release allocated buffers
849 
850  // Release IO
852 
853  _callback = nullptr;
854  }
855  }
856 
858  {
859  uint32_t device_fourcc = id;
860  char fourcc_buff[sizeof(device_fourcc)+1];
861  librealsense::copy(fourcc_buff, &device_fourcc, sizeof(device_fourcc));
862  fourcc_buff[sizeof(device_fourcc)] = 0;
863  return fourcc_buff;
864  }
865 
867  {
868  char buff[1]={};
869  if (write(_stop_pipe_fd[1], buff, 1) < 0)
870  {
871  throw linux_backend_exception("Could not signal video capture thread to stop. Error write to pipe.");
872  }
873  }
874 
876  {
877  using namespace std::chrono;
878 
879  // get current time
880  auto now = system_clock::now();
881 
882  // get number of milliseconds for the current second
883  // (remainder after division into seconds)
884  auto ms = duration_cast<milliseconds>(now.time_since_epoch()) % 1000;
885 
886  // convert to std::time_t in order to convert to std::tm (broken time)
887  auto timer = system_clock::to_time_t(now);
888 
889  // convert to broken time
890  std::tm bt = *std::localtime(&timer);
891 
892  std::ostringstream oss;
893 
894  oss << std::put_time(&bt, "%H:%M:%S"); // HH:MM:SS
895  oss << '.' << std::setfill('0') << std::setw(3) << ms.count();
896  return oss.str();
897  }
898 
900  {
901  fd_set fds{};
902  FD_ZERO(&fds);
903  for (auto fd : _fds)
904  {
905  FD_SET(fd, &fds);
906  }
907 
908  struct timespec mono_time;
909  int ret = clock_gettime(CLOCK_MONOTONIC, &mono_time);
910  if (ret) throw linux_backend_exception("could not query time!");
911 
912  struct timeval expiration_time = { mono_time.tv_sec + 5, mono_time.tv_nsec / 1000 };
913  int val = 0;
914 
915  auto realtime = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch()).count();
916  auto time_since_epoch = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::steady_clock::now().time_since_epoch()).count();
917  LOG_DEBUG_V4L("Select initiated at " << time_in_HH_MM_SS_MMM() << ", mono time " << time_since_epoch << ", host time " << realtime );
918  do {
919  struct timeval remaining;
920  ret = clock_gettime(CLOCK_MONOTONIC, &mono_time);
921  if (ret) throw linux_backend_exception("could not query time!");
922 
923  struct timeval current_time = { mono_time.tv_sec, mono_time.tv_nsec / 1000 };
924  timersub(&expiration_time, &current_time, &remaining);
925  if (timercmp(&current_time, &expiration_time, <)) {
926  val = select(_max_fd + 1, &fds, nullptr, nullptr, &remaining);
927  }
928  else {
929  val = 0;
930  LOG_DEBUG_V4L("Select timeouted");
931  }
932 
933  if (val< 0)
934  LOG_DEBUG_V4L("Select interrupted, val = " << val << ", error = " << errno);
935  } while (val < 0 && errno == EINTR);
936 
937  LOG_DEBUG_V4L("Select done, val = " << val << " at " << time_in_HH_MM_SS_MMM());
938  if(val < 0)
939  {
940  _is_capturing = false;
941  _is_started = false;
942 
943  // Notify kernel
944  streamoff();
945  }
946  else
947  {
948  if(val > 0)
949  {
950  if(FD_ISSET(_stop_pipe_fd[0], &fds) || FD_ISSET(_stop_pipe_fd[1], &fds))
951  {
952  if(!_is_capturing)
953  {
954  LOG_INFO("V4L stream is closed");
955  return;
956  }
957  else
958  {
959  LOG_ERROR("Stop pipe was signalled during streaming");
960  return;
961  }
962  }
963  else // Check and acquire data buffers from kernel
964  {
965  bool md_extracted = false;
966  bool keep_md = false;
967  bool wa_applied = false;
968  buffers_mgr buf_mgr(_use_memory_map);
970  {
971  buf_mgr = _buf_dispatch; // Handle over MD buffer from the previous cycle
972  md_extracted = true;
973  wa_applied = true;
974  _buf_dispatch.set_md_attributes(0,nullptr);
975  }
976  // RAII to handle exceptions
977  std::unique_ptr<int, std::function<void(int*)> > md_poller(new int(0),
978  [this,&buf_mgr,&md_extracted,&keep_md,&fds](int* d)
979  {
980  if (!md_extracted)
981  {
982  LOG_DEBUG_V4L("MD Poller read md ");
983  acquire_metadata(buf_mgr,fds);
984  if (buf_mgr.metadata_size())
985  {
986  if (keep_md) // store internally for next poll cycle
987  {
988  auto fn = *(uint32_t*)((char*)(buf_mgr.metadata_start())+28);
989  auto mdb = buf_mgr.get_buffers().at(e_metadata_buf);
990  LOG_DEBUG_V4L("Poller stores buf for fd " << std::dec << mdb._file_desc
991  << " ,seq = " << mdb._dq_buf.sequence << " v4l_buf " << mdb._dq_buf.index
992  << " , metadata size = " << (int)buf_mgr.metadata_size()
993  << ", fn = " << fn);
994  _buf_dispatch = buf_mgr; // TODO keep metadata only as dispatch may hold video buf from previous cycle
995  buf_mgr.handle_buffer(e_metadata_buf,-1); // transfer new buffer request to next cycle
996  }
997  else // Discard collected metadata buffer
998  {
999  LOG_DEBUG_V4L("Discard md buffer");
1000  auto md_buf = buf_mgr.get_buffers().at(e_metadata_buf);
1001  if (md_buf._data_buf)
1002  md_buf._data_buf->request_next_frame(md_buf._file_desc,true);
1003  }
1004  }
1005  }
1006  delete d;
1007  });
1008 
1009  if(FD_ISSET(_fd, &fds))
1010  {
1011  FD_CLR(_fd,&fds);
1012  v4l2_buffer buf = {};
1013  buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
1014  buf.memory = _use_memory_map ? V4L2_MEMORY_MMAP : V4L2_MEMORY_USERPTR;
1015  if(xioctl(_fd, VIDIOC_DQBUF, &buf) < 0)
1016  {
1017  LOG_DEBUG_V4L("Dequeued empty buf for fd " << std::dec << _fd);
1018  }
1019  LOG_DEBUG_V4L("Dequeued buf " << std::dec << buf.index << " for fd " << _fd << " seq " << buf.sequence);
1020 
1021  auto buffer = _buffers[buf.index];
1022  buf_mgr.handle_buffer(e_video_buf,_fd, buf,buffer);
1023 
1024  if (_is_started)
1025  {
1026  if(buf.bytesused == 0)
1027  {
1028  LOG_DEBUG_V4L("Empty video frame arrived, index " << buf.index);
1029  return;
1030  }
1031 
1032  // Relax the required frame size for compressed formats, i.e. MJPG, Z16H
1033  // Drop partial and overflow frames (assumes D4XX metadata only)
1034  bool compressed_format = val_in_range(_profile.format, { 0x4d4a5047U , 0x5a313648U});
1035  bool partial_frame = (!compressed_format && (buf.bytesused < buffer->get_full_length() - MAX_META_DATA_SIZE));
1036  bool overflow_frame = (buf.bytesused == buffer->get_length_frame_only() + MAX_META_DATA_SIZE);
1037  if (partial_frame || overflow_frame)
1038  {
1039  auto percentage = (100 * buf.bytesused) / buffer->get_full_length();
1040  std::stringstream s;
1041  if (partial_frame)
1042  {
1043  s << "Incomplete video frame detected!\nSize " << buf.bytesused
1044  << " out of " << buffer->get_full_length() << " bytes (" << percentage << "%)";
1045  if (overflow_frame)
1046  {
1047  s << ". Overflow detected: payload size " << buffer->get_length_frame_only();
1048  LOG_ERROR("Corrupted UVC frame data, underflow and overflow reported:\n" << s.str().c_str());
1049  }
1050  }
1051  else
1052  {
1053  if (overflow_frame)
1054  s << "overflow video frame detected!\nSize " << buf.bytesused
1055  << ", payload size " << buffer->get_length_frame_only();
1056  }
1057  LOG_WARNING("Incomplete frame received: " << s.str()); // Ev -try1
1059 
1060  _error_handler(n);
1061  // Check if metadata was already allocated
1062  if (buf_mgr.metadata_size())
1063  {
1064  LOG_WARNING("Metadata was present when partial frame arrived, mark md as extracted");
1065  md_extracted = true;
1066  LOG_DEBUG_V4L("Discarding md due to invalid video payload");
1067  auto md_buf = buf_mgr.get_buffers().at(e_metadata_buf);
1068  md_buf._data_buf->request_next_frame(md_buf._file_desc,true);
1069  }
1070  }
1071  else
1072  {
1073  auto timestamp = (double)buf.timestamp.tv_sec*1000.f + (double)buf.timestamp.tv_usec/1000.f;
1075 
1076  // Read metadata. Metadata node performs a blocking call to ensure video and metadata sync
1077  acquire_metadata(buf_mgr,fds,compressed_format);
1078  md_extracted = true;
1079 
1080  if (wa_applied)
1081  {
1082  auto fn = *(uint32_t*)((char*)(buf_mgr.metadata_start())+28);
1083  LOG_DEBUG_V4L("Extracting md buff, fn = " << fn);
1084  }
1085 
1086  auto frame_sz = buf_mgr.md_node_present() ? buf.bytesused :
1087  std::min(buf.bytesused - buf_mgr.metadata_size(), buffer->get_length_frame_only());
1088  frame_object fo{ frame_sz, buf_mgr.metadata_size(),
1090 
1091  buffer->attach_buffer(buf);
1092  buf_mgr.handle_buffer(e_video_buf,-1); // transfer new buffer request to the frame callback
1093 
1094  if (buf_mgr.verify_vd_md_sync())
1095  {
1096  //Invoke user callback and enqueue next frame
1097  _callback(_profile, fo, [buf_mgr]() mutable {
1098  buf_mgr.request_next_frame();
1099  });
1100  }
1101  else
1102  {
1103  LOG_WARNING("Video frame dropped, video and metadata buffers inconsistency");
1104  }
1105  }
1106  }
1107  else
1108  {
1109  LOG_DEBUG_V4L("Video frame arrived in idle mode."); // TODO - verification
1110  }
1111  }
1112  else
1113  {
1114  if (_is_started)
1115  keep_md = true;
1116  LOG_DEBUG("FD_ISSET: no data on video node sink");
1117  }
1118  }
1119  }
1120  else // (val==0)
1121  {
1122  LOG_WARNING("Frames didn't arrived within 5 seconds");
1123  librealsense::notification n = {RS2_NOTIFICATION_CATEGORY_FRAMES_TIMEOUT, 0, RS2_LOG_SEVERITY_WARN, "Frames didn't arrived within 5 seconds"};
1124 
1125  _error_handler(n);
1126  }
1127  }
1128  }
1129 
1130  void v4l_uvc_device::acquire_metadata(buffers_mgr & buf_mgr,fd_set &, bool compressed_format)
1131  {
1132  if (has_metadata())
1133  buf_mgr.set_md_from_video_node(compressed_format);
1134  else
1135  buf_mgr.set_md_attributes(0, nullptr);
1136  }
1137 
1139  {
1140  if (state == D0 && _state == D3)
1141  {
1143  }
1144  if (state == D3 && _state == D0)
1145  {
1146  close(_profile);
1148  }
1149  _state = state;
1150  }
1151 
1152  bool v4l_uvc_device::set_xu(const extension_unit& xu, uint8_t control, const uint8_t* data, int size)
1153  {
1154  uvc_xu_control_query q = {static_cast<uint8_t>(xu.unit), control, UVC_SET_CUR,
1155  static_cast<uint16_t>(size), const_cast<uint8_t *>(data)};
1156  if(xioctl(_fd, UVCIOC_CTRL_QUERY, &q) < 0)
1157  {
1158  if (errno == EIO || errno == EAGAIN) // TODO: Log?
1159  return false;
1160 
1161  throw linux_backend_exception("set_xu(...). xioctl(UVCIOC_CTRL_QUERY) failed");
1162  }
1163 
1164  return true;
1165  }
1166  bool v4l_uvc_device::get_xu(const extension_unit& xu, uint8_t control, uint8_t* data, int size) const
1167  {
1168  uvc_xu_control_query q = {static_cast<uint8_t>(xu.unit), control, UVC_GET_CUR,
1169  static_cast<uint16_t>(size), const_cast<uint8_t *>(data)};
1170  if(xioctl(_fd, UVCIOC_CTRL_QUERY, &q) < 0)
1171  {
1172  if (errno == EIO || errno == EAGAIN || errno == EBUSY) // TODO: Log?
1173  return false;
1174 
1175  throw linux_backend_exception("get_xu(...). xioctl(UVCIOC_CTRL_QUERY) failed");
1176  }
1177 
1178  return true;
1179  }
1181  {
1183  __u16 size = 0;
1184  //__u32 value = 0; // all of the real sense extended controls are up to 4 bytes
1185  // checking return value for UVC_GET_LEN and allocating
1186  // appropriately might be better
1187  //__u8 * data = (__u8 *)&value;
1188  // MS XU controls are partially supported only
1189  struct uvc_xu_control_query xquery = {};
1190  memset(&xquery, 0, sizeof(xquery));
1191  xquery.query = UVC_GET_LEN;
1192  xquery.size = 2; // size seems to always be 2 for the LEN query, but
1193  //doesn't seem to be documented. Use result for size
1194  //in all future queries of the same control number
1195  xquery.selector = control;
1196  xquery.unit = xu.unit;
1197  xquery.data = (__u8 *)&size;
1198 
1199  if(-1 == ioctl(_fd,UVCIOC_CTRL_QUERY,&xquery)){
1200  throw linux_backend_exception("xioctl(UVC_GET_LEN) failed");
1201  }
1202 
1203  assert(size<=len);
1204 
1205  std::vector<uint8_t> buf;
1206  auto buf_size = std::max((size_t)len,sizeof(__u32));
1207  buf.resize(buf_size);
1208 
1209  xquery.query = UVC_GET_MIN;
1210  xquery.size = size;
1211  xquery.selector = control;
1212  xquery.unit = xu.unit;
1213  xquery.data = buf.data();
1214  if(-1 == ioctl(_fd,UVCIOC_CTRL_QUERY,&xquery)){
1215  throw linux_backend_exception("xioctl(UVC_GET_MIN) failed");
1216  }
1217  result.min.resize(buf_size);
1218  std::copy(buf.begin(), buf.end(), result.min.begin());
1219 
1220  xquery.query = UVC_GET_MAX;
1221  xquery.size = size;
1222  xquery.selector = control;
1223  xquery.unit = xu.unit;
1224  xquery.data = buf.data();
1225  if(-1 == ioctl(_fd,UVCIOC_CTRL_QUERY,&xquery)){
1226  throw linux_backend_exception("xioctl(UVC_GET_MAX) failed");
1227  }
1228  result.max.resize(buf_size);
1229  std::copy(buf.begin(), buf.end(), result.max.begin());
1230 
1231  xquery.query = UVC_GET_DEF;
1232  xquery.size = size;
1233  xquery.selector = control;
1234  xquery.unit = xu.unit;
1235  xquery.data = buf.data();
1236  if(-1 == ioctl(_fd,UVCIOC_CTRL_QUERY,&xquery)){
1237  throw linux_backend_exception("xioctl(UVC_GET_DEF) failed");
1238  }
1239  result.def.resize(buf_size);
1240  std::copy(buf.begin(), buf.end(), result.def.begin());
1241 
1242  xquery.query = UVC_GET_RES;
1243  xquery.size = size;
1244  xquery.selector = control;
1245  xquery.unit = xu.unit;
1246  xquery.data = buf.data();
1247  if(-1 == ioctl(_fd,UVCIOC_CTRL_QUERY,&xquery)){
1248  throw linux_backend_exception("xioctl(UVC_GET_CUR) failed");
1249  }
1250  result.step.resize(buf_size);
1251  std::copy(buf.begin(), buf.end(), result.step.begin());
1252 
1253  return result;
1254  }
1255 
1257  {
1258  struct v4l2_control control = {get_cid(opt), 0};
1259  if (xioctl(_fd, VIDIOC_G_CTRL, &control) < 0)
1260  {
1261  if (errno == EIO || errno == EAGAIN) // TODO: Log?
1262  return false;
1263 
1264  throw linux_backend_exception("xioctl(VIDIOC_G_CTRL) failed");
1265  }
1266 
1267  if (RS2_OPTION_ENABLE_AUTO_EXPOSURE==opt) { control.value = (V4L2_EXPOSURE_MANUAL==control.value) ? 0 : 1; }
1268  value = control.value;
1269 
1270  return true;
1271  }
1272 
1274  {
1275  struct v4l2_control control = {get_cid(opt), value};
1276  if (RS2_OPTION_ENABLE_AUTO_EXPOSURE==opt) { control.value = value ? V4L2_EXPOSURE_APERTURE_PRIORITY : V4L2_EXPOSURE_MANUAL; }
1277  if (xioctl(_fd, VIDIOC_S_CTRL, &control) < 0)
1278  {
1279  if (errno == EIO || errno == EAGAIN) // TODO: Log?
1280  return false;
1281 
1282  throw linux_backend_exception("xioctl(VIDIOC_S_CTRL) failed");
1283  }
1284 
1285  return true;
1286  }
1287 
1289  {
1290  // Auto controls range is trimed to {0,1} range
1292  {
1293  static const int32_t min = 0, max = 1, step = 1, def = 1;
1294  control_range range(min, max, step, def);
1295 
1296  return range;
1297  }
1298 
1299  struct v4l2_queryctrl query = {};
1300  query.id = get_cid(option);
1301  if (xioctl(_fd, VIDIOC_QUERYCTRL, &query) < 0)
1302  {
1303  // Some controls (exposure, auto exposure, auto hue) do not seem to work on V4L2
1304  // Instead of throwing an error, return an empty range. This will cause this control to be omitted on our UI sample.
1305  // TODO: Figure out what can be done about these options and make this work
1306  query.minimum = query.maximum = 0;
1307  }
1308 
1309  control_range range(query.minimum, query.maximum, query.step, query.default_value);
1310 
1311  return range;
1312  }
1313 
1314  std::vector<stream_profile> v4l_uvc_device::get_profiles() const
1315  {
1316  std::vector<stream_profile> results;
1317 
1318  // Retrieve the caps one by one, first get pixel format, then sizes, then
1319  // frame rates. See http://linuxtv.org/downloads/v4l-dvb-apis for reference.
1320  v4l2_fmtdesc pixel_format = {};
1321  pixel_format.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
1322  while (ioctl(_fd, VIDIOC_ENUM_FMT, &pixel_format) == 0)
1323  {
1324  v4l2_frmsizeenum frame_size = {};
1325  frame_size.pixel_format = pixel_format.pixelformat;
1326 
1327  uint32_t fourcc = (const big_endian<int> &)pixel_format.pixelformat;
1328 
1329  if (pixel_format.pixelformat == 0)
1330  {
1331  // Microsoft Depth GUIDs for R400 series are not yet recognized
1332  // by the Linux kernel, but they do not require a patch, since there
1333  // are "backup" Z16 and Y8 formats in place
1334  std::set<std::string> known_problematic_formats = {
1335  "00000050-0000-0010-8000-00aa003",
1336  "00000032-0000-0010-8000-00aa003",
1337  };
1338 
1339  if (std::find(known_problematic_formats.begin(),
1340  known_problematic_formats.end(),
1341  (const char*)pixel_format.description) ==
1342  known_problematic_formats.end())
1343  {
1344  const std::string s(to_string() << "!" << pixel_format.description);
1345  std::regex rgx("!([0-9a-f]+)-.*");
1346  std::smatch match;
1347 
1348  if (std::regex_search(s.begin(), s.end(), match, rgx))
1349  {
1350  std::stringstream ss;
1351  ss << match[1];
1352  int id;
1353  ss >> std::hex >> id;
1354  fourcc = (const big_endian<int> &)id;
1355 
1356  auto format_str = fourcc_to_string(id);
1357  LOG_WARNING("Pixel format " << pixel_format.description << " likely requires patch for fourcc code " << format_str << "!");
1358  }
1359  }
1360  }
1361  else
1362  {
1363  LOG_DEBUG("Recognized pixel-format " << pixel_format.description);
1364  }
1365 
1366  while (ioctl(_fd, VIDIOC_ENUM_FRAMESIZES, &frame_size) == 0)
1367  {
1368  v4l2_frmivalenum frame_interval = {};
1369  frame_interval.pixel_format = pixel_format.pixelformat;
1370  frame_interval.width = frame_size.discrete.width;
1371  frame_interval.height = frame_size.discrete.height;
1372  while (ioctl(_fd, VIDIOC_ENUM_FRAMEINTERVALS, &frame_interval) == 0)
1373  {
1374  if (frame_interval.type == V4L2_FRMIVAL_TYPE_DISCRETE)
1375  {
1376  if (frame_interval.discrete.numerator != 0)
1377  {
1378  auto fps =
1379  static_cast<float>(frame_interval.discrete.denominator) /
1380  static_cast<float>(frame_interval.discrete.numerator);
1381 
1382  stream_profile p{};
1383  p.format = fourcc;
1384  p.width = frame_size.discrete.width;
1385  p.height = frame_size.discrete.height;
1386  p.fps = fps;
1387  if (fourcc != 0) results.push_back(p);
1388  }
1389  }
1390 
1391  ++frame_interval.index;
1392  }
1393 
1394  ++frame_size.index;
1395  }
1396 
1397  ++pixel_format.index;
1398  }
1399  return results;
1400  }
1401 
1403  {
1404  _named_mtx->lock();
1405  }
1407  {
1408  _named_mtx->unlock();
1409  }
1410 
1412  {
1413  switch(option)
1414  {
1415  case RS2_OPTION_BACKLIGHT_COMPENSATION: return V4L2_CID_BACKLIGHT_COMPENSATION;
1416  case RS2_OPTION_BRIGHTNESS: return V4L2_CID_BRIGHTNESS;
1417  case RS2_OPTION_CONTRAST: return V4L2_CID_CONTRAST;
1418  case RS2_OPTION_EXPOSURE: return V4L2_CID_EXPOSURE_ABSOLUTE; // Is this actually valid? I'm getting a lot of VIDIOC error 22s...
1419  case RS2_OPTION_GAIN: return V4L2_CID_GAIN;
1420  case RS2_OPTION_GAMMA: return V4L2_CID_GAMMA;
1421  case RS2_OPTION_HUE: return V4L2_CID_HUE;
1422  case RS2_OPTION_SATURATION: return V4L2_CID_SATURATION;
1423  case RS2_OPTION_SHARPNESS: return V4L2_CID_SHARPNESS;
1424  case RS2_OPTION_WHITE_BALANCE: return V4L2_CID_WHITE_BALANCE_TEMPERATURE;
1425  case RS2_OPTION_ENABLE_AUTO_EXPOSURE: return V4L2_CID_EXPOSURE_AUTO; // Automatic gain/exposure control
1426  case RS2_OPTION_ENABLE_AUTO_WHITE_BALANCE: return V4L2_CID_AUTO_WHITE_BALANCE;
1427  case RS2_OPTION_POWER_LINE_FREQUENCY : return V4L2_CID_POWER_LINE_FREQUENCY;
1428  case RS2_OPTION_AUTO_EXPOSURE_PRIORITY: return V4L2_CID_EXPOSURE_AUTO_PRIORITY;
1429  default: throw linux_backend_exception(to_string() << "no v4l2 cid for option " << option);
1430  }
1431  }
1432 
1434  {
1435  try
1436  {
1437  while(_is_capturing)
1438  {
1439  poll();
1440  }
1441  }
1442  catch (const std::exception& ex)
1443  {
1444  LOG_ERROR(ex.what());
1445 
1447 
1448  _error_handler(n);
1449  }
1450  }
1451 
1453  {
1454  return !_use_memory_map;
1455  }
1456 
1458  {
1459  stream_ctl_on(_fd);
1460  }
1461 
1463  {
1464  stream_off(_fd);
1465  }
1466 
1468  {
1469  req_io_buff(_fd, num, _name,
1470  _use_memory_map ? V4L2_MEMORY_MMAP : V4L2_MEMORY_USERPTR,
1471  V4L2_BUF_TYPE_VIDEO_CAPTURE);
1472  }
1473 
1475  {
1476  if (buffers)
1477  {
1478  for(size_t i = 0; i < buffers; ++i)
1479  {
1480  _buffers.push_back(std::make_shared<buffer>(_fd, V4L2_BUF_TYPE_VIDEO_CAPTURE, _use_memory_map, i));
1481  }
1482  }
1483  else
1484  {
1485  for(size_t i = 0; i < _buffers.size(); i++)
1486  {
1487  _buffers[i]->detach_buffer();
1488  }
1489  _buffers.resize(0);
1490  }
1491  }
1492 
1494  {
1495  _fd = open(_name.c_str(), O_RDWR | O_NONBLOCK, 0);
1496  if(_fd < 0)
1497  throw linux_backend_exception(to_string() <<__FUNCTION__ << " Cannot open '" << _name);
1498 
1499  if (pipe(_stop_pipe_fd) < 0)
1500  throw linux_backend_exception(to_string() <<__FUNCTION__ << " Cannot create pipe!");
1501 
1502  if (_fds.size())
1503  throw linux_backend_exception(to_string() <<__FUNCTION__ << " Device descriptor is already allocated");
1504 
1505  _fds.insert(_fds.end(),{_fd,_stop_pipe_fd[0],_stop_pipe_fd[1]});
1506  _max_fd = *std::max_element(_fds.begin(),_fds.end());
1507 
1508  v4l2_capability cap = {};
1509  if(xioctl(_fd, VIDIOC_QUERYCAP, &cap) < 0)
1510  {
1511  if(errno == EINVAL)
1512  throw linux_backend_exception(_name + " is not V4L2 device");
1513  else
1514  throw linux_backend_exception("xioctl(VIDIOC_QUERYCAP) failed");
1515  }
1516  if(!(cap.capabilities & V4L2_CAP_VIDEO_CAPTURE))
1517  throw linux_backend_exception(_name + " is no video capture device");
1518 
1519  if(!(cap.capabilities & V4L2_CAP_STREAMING))
1520  throw linux_backend_exception(_name + " does not support streaming I/O");
1521 
1522  // Select video input, video standard and tune here.
1523  v4l2_cropcap cropcap = {};
1524  cropcap.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
1525  if(xioctl(_fd, VIDIOC_CROPCAP, &cropcap) == 0)
1526  {
1527  v4l2_crop crop = {};
1528  crop.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
1529  crop.c = cropcap.defrect; // reset to default
1530  if(xioctl(_fd, VIDIOC_S_CROP, &crop) < 0)
1531  {
1532  switch (errno)
1533  {
1534  case EINVAL: break; // Cropping not supported
1535  default: break; // Errors ignored
1536  }
1537  }
1538  } else {} // Errors ignored
1539  }
1540 
1542  {
1543  if(::close(_fd) < 0)
1544  throw linux_backend_exception("v4l_uvc_device: close(_fd) failed");
1545 
1546  if(::close(_stop_pipe_fd[0]) < 0)
1547  throw linux_backend_exception("v4l_uvc_device: close(_stop_pipe_fd[0]) failed");
1548  if(::close(_stop_pipe_fd[1]) < 0)
1549  throw linux_backend_exception("v4l_uvc_device: close(_stop_pipe_fd[1]) failed");
1550 
1551  _fd = 0;
1552  _stop_pipe_fd[0] = _stop_pipe_fd[1] = 0;
1553  _fds.clear();
1554  }
1555 
1557  {
1558  v4l2_format fmt = {};
1559  fmt.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
1560  fmt.fmt.pix.width = profile.width;
1561  fmt.fmt.pix.height = profile.height;
1562  fmt.fmt.pix.pixelformat = (const big_endian<int> &)profile.format;
1563  fmt.fmt.pix.field = V4L2_FIELD_NONE;
1564  if(xioctl(_fd, VIDIOC_S_FMT, &fmt) < 0)
1565  {
1566  throw linux_backend_exception("xioctl(VIDIOC_S_FMT) failed");
1567  }
1568  else
1569  LOG_INFO("Video node was successfully configured to " << fourcc_to_string(fmt.fmt.pix.pixelformat) << " format" <<", fd " << std::dec << _fd);
1570 
1571  LOG_INFO("Trying to configure fourcc " << fourcc_to_string(fmt.fmt.pix.pixelformat));
1572  }
1573 
1575  v4l_uvc_device(info,use_memory_map),
1576  _md_fd(0),
1577  _md_name(info.metadata_node_id)
1578  {
1579  }
1580 
1582  {
1583  }
1584 
1586  {
1587  // Metadata stream shall be configured first to allow sync with video node
1589 
1590  // Invoke UVC streaming request
1592 
1593  }
1594 
1596  {
1598 
1600  }
1601 
1603  {
1605 
1606  req_io_buff(_md_fd, num, _name,
1607  _use_memory_map ? V4L2_MEMORY_MMAP : V4L2_MEMORY_USERPTR,
1609  }
1610 
1612  {
1614 
1615  if (buffers)
1616  {
1617  for(size_t i = 0; i < buffers; ++i)
1618  {
1619  _md_buffers.push_back(std::make_shared<buffer>(_md_fd, LOCAL_V4L2_BUF_TYPE_META_CAPTURE, _use_memory_map, i));
1620  }
1621  }
1622  else
1623  {
1624  for(size_t i = 0; i < _buffers.size(); i++)
1625  {
1626  _md_buffers[i]->detach_buffer();
1627  }
1628  _md_buffers.resize(0);
1629  }
1630  }
1631 
1633  {
1635 
1636  if (_md_fd>0)
1637  throw linux_backend_exception(to_string() << _md_name << " descriptor is already opened");
1638 
1639  _md_fd = open(_md_name.c_str(), O_RDWR | O_NONBLOCK, 0);
1640  if(_md_fd < 0)
1641  throw linux_backend_exception(to_string() << "Cannot open '" << _md_name);
1642 
1643  //The minimal video/metadata nodes syncer will be implemented by using two blocking calls:
1644  // 1. Obtain video node data.
1645  // 2. Obtain metadata
1646  // To revert to multiplexing mode uncomment the next line
1647  _fds.push_back(_md_fd);
1648  _max_fd = *std::max_element(_fds.begin(),_fds.end());
1649 
1650  v4l2_capability cap = {};
1651  if(xioctl(_md_fd, VIDIOC_QUERYCAP, &cap) < 0)
1652  {
1653  if(errno == EINVAL)
1654  throw linux_backend_exception(_md_name + " is no V4L2 device");
1655  else
1656  throw linux_backend_exception(_md_name + " xioctl(VIDIOC_QUERYCAP) for metadata failed");
1657  }
1658 
1659  if(!(cap.capabilities & V4L2_CAP_META_CAPTURE))
1660  throw linux_backend_exception(_md_name + " is not metadata capture device");
1661 
1662  if(!(cap.capabilities & V4L2_CAP_STREAMING))
1663  throw linux_backend_exception(_md_name + " does not support metadata streaming I/O");
1664  }
1665 
1666 
1668  {
1670 
1671  if(::close(_md_fd) < 0)
1672  throw linux_backend_exception("v4l_uvc_meta_device: close(_md_fd) failed");
1673 
1674  _md_fd = 0;
1675  }
1676 
1678  {
1679  // Select video node streaming format
1680  v4l_uvc_device::set_format(profile);
1681 
1682  // Configure metadata node stream format
1683  v4l2_format fmt{ };
1685 
1686  if (xioctl(_md_fd, VIDIOC_G_FMT, &fmt))
1687  throw linux_backend_exception(_md_name + " ioctl(VIDIOC_G_FMT) for metadata node failed");
1688 
1690  throw linux_backend_exception("ioctl(VIDIOC_G_FMT): " + _md_name + " node is not metadata capture");
1691 
1692  bool success = false;
1693  for (const uint32_t& request : { V4L2_META_FMT_D4XX, V4L2_META_FMT_UVC})
1694  {
1695  // Configure metadata format - try d4xx, then fallback to currently retrieve UVC default header of 12 bytes
1696  memcpy(fmt.fmt.raw_data,&request,sizeof(request));
1697 
1698  if(xioctl(_md_fd, VIDIOC_S_FMT, &fmt) >= 0)
1699  {
1700  LOG_INFO("Metadata node was successfully configured to " << fourcc_to_string(request) << " format" <<", fd " << std::dec <<_md_fd);
1701  success =true;
1702  break;
1703  }
1704  else
1705  {
1706  LOG_WARNING("Metadata node configuration failed for " << fourcc_to_string(request));
1707  }
1708  }
1709 
1710  if (!success)
1711  throw linux_backend_exception(_md_name + " ioctl(VIDIOC_S_FMT) for metadata node failed");
1712 
1713  }
1714 
1716  {
1717  // Meta node to be initialized first to enforce initial sync
1718  for (auto&& buf : _md_buffers) buf->prepare_for_streaming(_md_fd);
1719 
1720  // Request streaming for video node
1722  }
1723 
1724  // Retrieve metadata from a dedicated UVC node. For kernels 4.16+
1725  void v4l_uvc_meta_device::acquire_metadata(buffers_mgr & buf_mgr,fd_set &fds, bool)
1726  {
1727  //Use non-blocking metadata node polling
1728  if(FD_ISSET(_md_fd, &fds))
1729  {
1730  // In scenario if [md+vid] ->[md] ->[md,vid] the third md should not be retrieved but wait for next select
1731  if (buf_mgr.metadata_size())
1732  {
1733  LOG_WARNING("Metadata override requested but avoided skipped");
1734  return;
1735  }
1736  FD_CLR(_md_fd,&fds);
1737 
1738  v4l2_buffer buf{};
1740  buf.memory = _use_memory_map ? V4L2_MEMORY_MMAP : V4L2_MEMORY_USERPTR;
1741 
1742  // W/O multiplexing this will create a blocking call for metadata node
1743  if(xioctl(_md_fd, VIDIOC_DQBUF, &buf) < 0)
1744  {
1745  LOG_DEBUG_V4L("Dequeued empty buf for md fd " << std::dec << _md_fd);
1746  }
1747 
1748  //V4l debugging message
1749  auto mdbuf = _md_buffers[buf.index]->get_frame_start();
1750  auto hwts = *(uint32_t*)((mdbuf+2));
1751  auto fn = *(uint32_t*)((mdbuf+38));
1752  LOG_DEBUG_V4L("Dequeued md buf " << std::dec << buf.index << " for fd " << _md_fd << " seq " << buf.sequence
1753  << " fn " << fn << " hw ts " << hwts
1754  << " v4lbuf ts usec " << buf.timestamp.tv_usec);
1755 
1756  auto buffer = _md_buffers[buf.index];
1758 
1759  if (!_is_started)
1760  LOG_INFO("Metadata frame arrived in idle mode.");
1761 
1762  static const size_t uvc_md_start_offset = sizeof(uvc_meta_buffer::ns) + sizeof(uvc_meta_buffer::sof);
1763 
1764  if (buf.bytesused > uvc_md_start_offset )
1765  {
1766  // The first uvc_md_start_offset bytes of metadata buffer are generated by host driver
1767  buf_mgr.set_md_attributes(buf.bytesused - uvc_md_start_offset,
1768  buffer->get_frame_start() + uvc_md_start_offset);
1769 
1771  buf_mgr.handle_buffer(e_metadata_buf,-1); // transfer new buffer request to the frame callback
1772  }
1773  else
1774  {
1775  LOG_DEBUG_V4L("Invalid md size: bytes used = " << buf.bytesused << " ,start offset=" << uvc_md_start_offset);
1776  // Zero-size buffers generate empty md. Non-zero partial bufs handled as errors
1777  if(buf.bytesused > 0)
1778  {
1779  std::stringstream s;
1780  s << "Invalid metadata payload, size " << buf.bytesused;
1781  LOG_WARNING(s.str());
1783  }
1784  }
1785 
1786  }
1787  }
1788 
1789  std::shared_ptr<uvc_device> v4l_backend::create_uvc_device(uvc_device_info info) const
1790  {
1791  auto v4l_uvc_dev = (!info.has_metadata_node) ? std::make_shared<v4l_uvc_device>(info) :
1792  std::make_shared<v4l_uvc_meta_device>(info);
1793 
1794  return std::make_shared<platform::retry_controls_work_around>(v4l_uvc_dev);
1795  }
1796 
1797  std::vector<uvc_device_info> v4l_backend::query_uvc_devices() const
1798  {
1799  std::vector<uvc_device_info> uvc_nodes;
1801  [&uvc_nodes](const uvc_device_info& i, const std::string&)
1802  {
1803  uvc_nodes.push_back(i);
1804  });
1805 
1806  return uvc_nodes;
1807  }
1808 
1809  std::shared_ptr<command_transfer> v4l_backend::create_usb_device(usb_device_info info) const
1810  {
1812  if(dev)
1813  return std::make_shared<platform::command_transfer_usb>(dev);
1814  return nullptr;
1815  }
1816 
1817  std::vector<usb_device_info> v4l_backend::query_usb_devices() const
1818  {
1819  auto device_infos = usb_enumerator::query_devices_info();
1820  // Give the device a chance to restart, if we don't catch
1821  // it, the watcher will find it later.
1822  if(tm_boot(device_infos)) {
1823  std::this_thread::sleep_for(std::chrono::milliseconds(2000));
1824  device_infos = usb_enumerator::query_devices_info();
1825  }
1826  return device_infos;
1827  }
1828 
1829  std::shared_ptr<hid_device> v4l_backend::create_hid_device(hid_device_info info) const
1830  {
1831  return std::make_shared<v4l_hid_device>(info);
1832  }
1833 
1834  std::vector<hid_device_info> v4l_backend::query_hid_devices() const
1835  {
1836  std::vector<hid_device_info> results;
1837  v4l_hid_device::foreach_hid_device([&](const hid_device_info& hid_dev_info){
1838  results.push_back(hid_dev_info);
1839  });
1840 
1841  return results;
1842  }
1843  std::shared_ptr<time_service> v4l_backend::create_time_service() const
1844  {
1845  return std::make_shared<os_time_service>();
1846  }
1847 
1848  std::shared_ptr<device_watcher> v4l_backend::create_device_watcher() const
1849  {
1850  return std::make_shared<polling_device_watcher>(this);
1851  }
1852 
1853  std::shared_ptr<backend> create_backend()
1854  {
1855  return std::make_shared<v4l_backend>();
1856  }
1857  }
1858 }
static const textual_icon lock
Definition: model-views.h:218
void set_format(stream_profile profile)
GLuint GLuint end
bool get_xu(const extension_unit &xu, uint8_t control, uint8_t *data, int size) const override
virtual void acquire_metadata(buffers_mgr &buf_mgr, fd_set &fds, bool compressed_format=false) override
std::istringstream istringstream
Definition: Arg.h:43
static rs_usb_device create_usb_device(const usb_device_info &info)
void negotiate_kernel_buffers(size_t num) const
buffer(int fd, v4l2_buf_type type, bool use_memory_map, uint32_t index)
GLuint const GLchar * name
virtual void negotiate_kernel_buffers(size_t num) const override
std::vector< usb_device_info > query_usb_devices() const override
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
Definition: rs_option.h:22
virtual void set_format(stream_profile profile) override
GLdouble s
static std::vector< usb_device_info > query_devices_info()
std::vector< std::shared_ptr< buffer > > _md_buffers
Definition: backend-v4l2.h:371
#define V4L2_META_FMT_D4XX
Definition: backend-v4l2.h:61
GLfloat GLfloat p
Definition: glext.h:12687
bool get_pu(rs2_option opt, int32_t &value) const override
#define LOG_WARNING(...)
Definition: src/types.h:241
bool val_in_range(const T &val, const std::initializer_list< T > &list)
Definition: src/types.h:174
GLsizei const GLchar *const * path
Definition: glext.h:4276
std::string fourcc_to_string(uint32_t id) const
GLfloat value
std::shared_ptr< hid_device > create_hid_device(hid_device_info info) const override
#define V4L2_CAP_META_CAPTURE
Definition: backend-v4l2.h:55
#define V4L2_META_FMT_UVC
Definition: backend-v4l2.h:52
void set_power_state(power_state state) override
const uint8_t MAX_META_DATA_SIZE
Definition: backend.h:34
static void foreach_uvc_device(std::function< void(const uvc_device_info &, const std::string &)> action)
std::array< kernel_buf_guard, e_max_kernel_buf_type > & get_buffers()
Definition: backend-v4l2.h:224
static void foreach_hid_device(std::function< void(const hid_device_info &)> action)
unsigned short uint16_t
Definition: stdint.h:79
static const std::map< usb_spec, std::string > usb_spec_names
Definition: usb-types.h:124
GLsizei const GLchar *const * string
void close(stream_profile) override
d
Definition: rmse.py:171
static uint32_t get_cid(rs2_option option)
GLuint entry
Definition: glext.h:10991
Definition: arg_fwd.hpp:23
GLdouble n
Definition: glext.h:1966
unsigned char uint8_t
Definition: stdint.h:78
e
Definition: rmse.py:177
std::shared_ptr< uvc_device > create_uvc_device(uvc_device_info info) const override
virtual bool has_metadata() const override
bool tm_boot(const std::vector< usb_device_info > &devices)
Definition: tm-boot.h:48
void sort(sort_type m_sort_type, const std::string &in, const std::string &out)
uint8_t * get_frame_start() const
Definition: backend-v4l2.h:138
GLuint num
Definition: glext.h:5648
std::vector< hid_device_info > query_hid_devices() const override
void stream_on(std::function< void(const notification &n)> error_handler) override
std::vector< stream_profile > get_profiles() const override
std::shared_ptr< backend > create_backend()
GLenum GLuint id
void set_md_attributes(uint8_t md_size, void *md_start)
Definition: backend-v4l2.h:182
GLuint index
void request_next_frame(int fd, bool force=false)
const size_t MAX_DEV_PARENT_DIR
GLenum cap
Definition: glext.h:8882
uint32_t get_full_length() const
Definition: backend-v4l2.h:135
GLenum GLuint GLenum GLsizei const GLchar * buf
GLenum GLsizei len
Definition: glext.h:3285
GLuint GLfloat * val
control_range get_pu_range(rs2_option option) const override
Definition: parser.hpp:154
def info(name, value, persistent=False)
Definition: test.py:301
not_this_one begin(...)
GLsizeiptr size
virtual void acquire_metadata(buffers_mgr &buf_mgr, fd_set &fds, bool compressed_format=false)
GLdouble GLdouble r
static std::map< std::string, int > _dev_mutex_cnt
Definition: backend-v4l2.h:114
std::shared_ptr< command_transfer > create_usb_device(usb_device_info info) const override
virtual void unmap_device_descriptor() override
void req_io_buff(int fd, uint32_t count, std::string dev_name, v4l2_memory mem_type, v4l2_buf_type type)
void handle_buffer(supported_kernel_buf_types buf_type, int file_desc, v4l2_buffer buf=v4l2_buffer(), std::shared_ptr< platform::buffer > data_buf=nullptr)
unsigned int uint32_t
Definition: stdint.h:80
static uint32_t get_dev_capabilities(const std::string dev_name)
virtual void map_device_descriptor() override
control_range get_xu_range(const extension_unit &xu, uint8_t control, int len) const override
std::shared_ptr< time_service > create_time_service() const override
constexpr auto LOCAL_V4L2_BUF_TYPE_META_CAPTURE
Definition: backend-v4l2.h:72
void stream_off(int fd, v4l2_buf_type type=V4L2_BUF_TYPE_VIDEO_CAPTURE)
def find(dir, mask)
Definition: file.py:25
def callback(frame)
Definition: t265_stereo.py:91
#define LOG_DEBUG_V4L(...)
Definition: backend-v4l2.h:68
static int xioctl(int fh, unsigned long request, void *arg)
void stream_ctl_on(int fd, v4l2_buf_type type=V4L2_BUF_TYPE_VIDEO_CAPTURE)
bool set_xu(const extension_unit &xu, uint8_t control, const uint8_t *data, int size) override
void probe_and_commit(stream_profile profile, frame_callback callback, int buffers) override
#define LOG_ERROR(...)
Definition: src/types.h:242
bool set_pu(rs2_option opt, int32_t value) override
const GLuint * buffers
action
Definition: enums.py:62
uint32_t get_length_frame_only() const
Definition: backend-v4l2.h:136
std::function< void(const notification &n)> _error_handler
Definition: backend.h:378
std::function< void(stream_profile, frame_object, std::function< void()>)> frame_callback
Definition: backend.h:177
double monotonic_to_realtime(double monotonic)
Definition: backend.cpp:26
LOG_INFO("Log message using LOG_INFO()")
static std::recursive_mutex _init_mutex
Definition: backend-v4l2.h:112
void attach_buffer(const v4l2_buffer &buf)
named_mutex(const std::string &device_path, unsigned timeout)
unsigned char byte
Definition: src/types.h:52
GLdouble GLdouble GLdouble q
GLbitfield GLuint64 timeout
GLenum type
std::unique_ptr< named_mutex > _named_mtx
Definition: backend-v4l2.h:336
virtual void allocate_io_buffers(size_t num) override
int min(int a, int b)
Definition: lz4s.c:73
void set_md_from_video_node(bool compressed)
GLint GLsizei count
static std::map< std::string, std::recursive_mutex > _dev_mutex
Definition: backend-v4l2.h:113
std::string time_in_HH_MM_SS_MMM()
virtual void prepare_capture_buffers() override
GLsizei range
int i
v4l_uvc_meta_device(const uvc_device_info &info, bool use_memory_map=false)
virtual void streamoff() const override
GLenum GLuint GLenum GLsizei length
GLuint res
Definition: glext.h:8856
signed int int32_t
Definition: stdint.h:77
#define LOG_DEBUG(...)
Definition: src/types.h:239
GLuint64 GLenum GLint fd
Definition: glext.h:7768
v4l_uvc_device(const uvc_device_info &info, bool use_memory_map=false)
virtual void streamon() const override
std::vector< std::shared_ptr< buffer > > _buffers
Definition: backend-v4l2.h:329
GLboolean * data
std::vector< uvc_device_info > query_uvc_devices() const override
std::shared_ptr< device_watcher > create_device_watcher() const override
GLuint64EXT * result
Definition: glext.h:10921
YYCODETYPE lhs
Definition: sqlite3.c:132469
Definition: parser.hpp:150
void copy(void *dst, void const *src, size_t size)
Definition: types.cpp:836
std::unique_ptr< std::thread > _thread
Definition: backend-v4l2.h:335
static usb_spec get_usb_connection_type(std::string path)
virtual void stop_data_capture() override
std::string to_string(T value)


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