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"
9 #include "backend-hid.h"
10 #include "backend.h"
11 #include "types.h"
12 #if defined(USING_UDEV)
13 #include "udev-device-watcher.h"
14 #else
15 #include "../polling-device-watcher.h"
16 #endif
17 #include "usb/usb-enumerator.h"
18 #include "usb/usb-device.h"
19 
20 #include <rsutils/string/from.h>
21 
22 #include <cassert>
23 #include <cstdlib>
24 #include <cstdio>
25 #include <cstring>
26 
27 #include <algorithm>
28 #include <functional>
29 #include <string>
30 #include <sstream>
31 #include <fstream>
32 #include <regex>
33 #include <thread>
34 #include <utility> // for pair
35 #include <chrono>
36 #include <thread>
37 #include <atomic>
38 #include <iomanip> // std::put_time
39 
40 #include <dirent.h>
41 #include <fcntl.h>
42 #include <unistd.h>
43 #include <limits.h>
44 #include <cmath>
45 #include <errno.h>
46 #include <sys/stat.h>
47 #include <sys/mman.h>
48 #include <sys/ioctl.h>
49 #include <sys/sysmacros.h> // minor(...), major(...)
50 #include <linux/usb/video.h>
51 #include <linux/media.h>
52 #include <linux/uvcvideo.h>
53 #include <linux/videodev2.h>
54 #include <regex>
55 #include <list>
56 
57 #include <cstddef> // offsetof
58 
59 #include <sys/signalfd.h>
60 #include <signal.h>
61 #pragma GCC diagnostic ignored "-Woverflow"
62 
63 const size_t MAX_DEV_PARENT_DIR = 10;
65 
66 //D457 Dev. TODO -shall be refactored into the kernel headers.
67 constexpr uint32_t RS_STREAM_CONFIG_0 = 0x4000;
68 constexpr uint32_t RS_CAMERA_CID_BASE = (V4L2_CTRL_CLASS_CAMERA | RS_STREAM_CONFIG_0);
84 
85 //const uint32_t RS_CAMERA_GENERIC_XU = (RS_CAMERA_CID_BASE+15); // RS_CAMERA_CID_HWMC duplicate??
86 constexpr uint32_t RS_CAMERA_CID_LASER_POWER_MODE = (RS_CAMERA_CID_BASE+16); // RS_CAMERA_CID_LASER_POWER duplicate ???
88 constexpr uint32_t RS_CAMERA_CID_LASER_POWER_LEVEL = (RS_CAMERA_CID_BASE+18); // RS_CAMERA_CID_MANUAL_LASER_POWER ??
90 constexpr uint32_t RS_CAMERA_CID_WHITE_BALANCE_MODE = (RS_CAMERA_CID_BASE+20); // Similar to RS_CAMERA_CID_EWB ??
92 constexpr uint32_t RS_CAMERA_CID_EMITTER_FREQUENCY = (RS_CAMERA_CID_BASE+22); // [MIPI - Select projector frequency values: 0->57[KHZ], 1->91[KHZ]
94 
95 /* refe4rence for kernel 4.9 to be removed
96 #define UVC_CID_GENERIC_XU (V4L2_CID_PRIVATE_BASE+15)
97 #define UVC_CID_LASER_POWER_MODE (V4L2_CID_PRIVATE_BASE+16)
98 #define UVC_CID_MANUAL_EXPOSURE (V4L2_CID_PRIVATE_BASE+17)
99 #define UVC_CID_LASER_POWER_LEVEL (V4L2_CID_PRIVATE_BASE+18)
100 #define UVC_CID_EXPOSURE_MODE (V4L2_CID_PRIVATE_BASE+19)
101 #define UVC_CID_WHITE_BALANCE_MODE (V4L2_CID_PRIVATE_BASE+20)
102 #define UVC_CID_PRESET (V4L2_CID_PRIVATE_BASE+21)
103 UVC_CID_MANUAL_EXPOSURE
104 */
105 #ifdef ANDROID
106 
107 // https://android.googlesource.com/platform/bionic/+/master/libc/include/bits/lockf.h
108 #define F_ULOCK 0
109 #define F_LOCK 1
110 #define F_TLOCK 2
111 #define F_TEST 3
112 
113 // https://android.googlesource.com/platform/bionic/+/master/libc/bionic/lockf.cpp
114 int lockf64(int fd, int cmd, off64_t length)
115 {
116  // Translate POSIX lockf into fcntl.
117  struct flock64 fl;
118  memset(&fl, 0, sizeof(fl));
119  fl.l_whence = SEEK_CUR;
120  fl.l_start = 0;
121  fl.l_len = length;
122 
123  if (cmd == F_ULOCK) {
124  fl.l_type = F_UNLCK;
125  cmd = F_SETLK64;
126  return fcntl(fd, F_SETLK64, &fl);
127  }
128 
129  if (cmd == F_LOCK) {
130  fl.l_type = F_WRLCK;
131  return fcntl(fd, F_SETLKW64, &fl);
132  }
133 
134  if (cmd == F_TLOCK) {
135  fl.l_type = F_WRLCK;
136  return fcntl(fd, F_SETLK64, &fl);
137  }
138  if (cmd == F_TEST) {
139  fl.l_type = F_RDLCK;
140  if (fcntl(fd, F_GETLK64, &fl) == -1) return -1;
141  if (fl.l_type == F_UNLCK || fl.l_pid == getpid()) return 0;
142  errno = EACCES;
143  return -1;
144  }
145 
146  errno = EINVAL;
147  return -1;
148 }
149 
150 int lockf(int fd, int cmd, off_t length)
151 {
152  return lockf64(fd, cmd, length);
153 }
154 #endif
155 
156 namespace librealsense
157 {
158  namespace platform
159  {
160  std::recursive_mutex named_mutex::_init_mutex;
161  std::map<std::string, std::recursive_mutex> named_mutex::_dev_mutex;
162  std::map<std::string, int> named_mutex::_dev_mutex_cnt;
163 
164  named_mutex::named_mutex(const std::string& device_path, unsigned timeout)
165  : _device_path(device_path),
166  _timeout(timeout), // TODO: try to lock with timeout
167  _fildes(-1),
168  _object_lock_counter(0)
169  {
170  _init_mutex.lock();
171  _dev_mutex[_device_path]; // insert a mutex for _device_path
172  if (_dev_mutex_cnt.find(_device_path) == _dev_mutex_cnt.end())
173  {
175  }
176  _init_mutex.unlock();
177  }
178 
180  {
181  try
182  {
183  unlock();
184  }
185  catch(...)
186  {
187  LOG_DEBUG( "Error while unlocking mutex" );
188  }
189  }
190 
192  {
193  std::lock_guard<std::mutex> lock(_mutex);
194  acquire();
195  }
196 
198  {
199  std::lock_guard<std::mutex> lock(_mutex);
200  release();
201  }
202 
204  {
205  std::lock_guard<std::mutex> lock(_mutex);
206  if (-1 == _fildes)
207  {
208  _fildes = open(_device_path.c_str(), O_RDWR, 0); //TODO: check
209  if(_fildes < 0)
210  return false;
211  }
212 
213  auto ret = lockf(_fildes, F_TLOCK, 0);
214  if (ret != 0)
215  return false;
216 
217  return true;
218  }
219 
221  {
222  _dev_mutex[_device_path].lock();
223  _dev_mutex_cnt[_device_path] += 1; //Advance counters even if throws because catch calls release()
225  if (_dev_mutex_cnt[_device_path] == 1)
226  {
227  if (-1 == _fildes)
228  {
229  _fildes = open(_device_path.c_str(), O_RDWR, 0); //TODO: check
230  if(0 > _fildes)
231  {
232  release();
233  throw linux_backend_exception(rsutils::string::from() << __FUNCTION__ << ": Cannot open '" << _device_path);
234  }
235  }
236 
237  auto ret = lockf(_fildes, F_LOCK, 0);
238  if (0 != ret)
239  {
240  release();
241  throw linux_backend_exception(rsutils::string::from() << __FUNCTION__ << ": Acquire failed");
242  }
243  }
244  }
245 
247  {
249  if (_object_lock_counter < 0)
250  {
252  return;
253  }
255  std::string err_msg;
256  if (_dev_mutex_cnt[_device_path] < 0)
257  {
259  throw linux_backend_exception(rsutils::string::from() << "Error: _dev_mutex_cnt[" << _device_path << "] < 0");
260  }
261 
262  if ((_dev_mutex_cnt[_device_path] == 0) && (-1 != _fildes))
263  {
264  auto ret = lockf(_fildes, F_ULOCK, 0);
265  if (0 != ret)
266  err_msg = "lockf(...) failed";
267  else
268  {
269  ret = close(_fildes);
270  if (0 != ret)
271  err_msg = "close(...) failed";
272  else
273  _fildes = -1;
274  }
275  }
276  _dev_mutex[_device_path].unlock();
277 
278  if (!err_msg.empty())
279  throw linux_backend_exception(err_msg);
280 
281  }
282 
283  static int xioctl(int fh, unsigned long request, void *arg)
284  {
285  int r=0;
286  do {
287  r = ioctl(fh, request, arg);
288  } while (r < 0 && errno == EINTR);
289  return r;
290  }
291 
292  buffer::buffer(int fd, v4l2_buf_type type, bool use_memory_map, uint32_t index)
293  : _type(type), _use_memory_map(use_memory_map), _index(index)
294  {
295  v4l2_buffer buf = {};
296  struct v4l2_plane planes[VIDEO_MAX_PLANES] = {};
297  buf.type = _type;
298  buf.memory = use_memory_map ? V4L2_MEMORY_MMAP : V4L2_MEMORY_USERPTR;
299  buf.index = index;
300  buf.m.offset = 0;
301  if (type == V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE) {
302  buf.m.planes = planes;
303  buf.length = VIDEO_MAX_PLANES;
304  }
305  if(xioctl(fd, VIDIOC_QUERYBUF, &buf) < 0)
306  throw linux_backend_exception("xioctl(VIDIOC_QUERYBUF) failed");
307 
308  // Prior to kernel 4.16 metadata payload was attached to the end of the video payload
309  uint8_t md_extra = (V4L2_BUF_TYPE_VIDEO_CAPTURE==type) ? MAX_META_DATA_SIZE : 0;
310  _original_length = buf.length;
311  _offset = buf.m.offset;
312  if (type == V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE) {
313  _original_length = buf.m.planes[0].length;
314  _offset = buf.m.planes[0].m.mem_offset;
315  md_extra = 0;
316  }
317  _length = _original_length + md_extra;
318 
319  if (use_memory_map)
320  {
321  _start = static_cast<uint8_t*>(mmap(nullptr, _original_length,
322  PROT_READ | PROT_WRITE, MAP_SHARED,
323  fd, _offset));
324  if(_start == MAP_FAILED)
325  throw linux_backend_exception("mmap failed");
326  }
327  else
328  {
329  //_length += (V4L2_BUF_TYPE_VIDEO_CAPTURE==type) ? MAX_META_DATA_SIZE : 0;
330  _start = static_cast<uint8_t*>(malloc( _length));
331  if (!_start) throw linux_backend_exception("User_p allocation failed!");
332  memset(_start, 0, _length);
333  }
334  }
335 
337  {
338  v4l2_buffer buf = {};
339  struct v4l2_plane planes[VIDEO_MAX_PLANES] = {};
340  buf.type = _type;
341  buf.memory = _use_memory_map ? V4L2_MEMORY_MMAP : V4L2_MEMORY_USERPTR;
342  buf.index = _index;
343  buf.length = _length;
344  if (_type == V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE) {
345  buf.m.planes = planes;
346  buf.length = 1;
347  }
348  if ( !_use_memory_map )
349  {
350  buf.m.userptr = reinterpret_cast<unsigned long>(_start);
351  }
352  if(xioctl(fd, VIDIOC_QBUF, &buf) < 0)
353  throw linux_backend_exception("xioctl(VIDIOC_QBUF) failed");
354  else
355  LOG_DEBUG_V4L("prepare_for_streaming fd " << std::dec << fd);
356  }
357 
359  {
360  if (_use_memory_map)
361  {
362  if(munmap(_start, _original_length) < 0)
363  linux_backend_exception("munmap");
364  }
365  else
366  {
367  free(_start);
368  }
369  }
370 
371  void buffer::attach_buffer(const v4l2_buffer& buf)
372  {
373  std::lock_guard<std::mutex> lock(_mutex);
374  _buf = buf;
375  _must_enqueue = true;
376  }
377 
379  {
380  std::lock_guard<std::mutex> lock(_mutex);
381  _must_enqueue = false;
382  }
383 
384  void buffer::request_next_frame(int fd, bool force)
385  {
386  std::lock_guard<std::mutex> lock(_mutex);
387 
388  if (_must_enqueue || force)
389  {
390  if (!_use_memory_map)
391  {
392  auto metadata_offset = get_full_length() - MAX_META_DATA_SIZE;
393  memset((uint8_t *)(get_frame_start()) + metadata_offset, 0, MAX_META_DATA_SIZE);
394  }
395 
396  LOG_DEBUG_V4L("Enqueue buf " << std::dec << _buf.index << " for fd " << fd);
397  if (xioctl(fd, VIDIOC_QBUF, &_buf) < 0)
398  {
399  LOG_ERROR("xioctl(VIDIOC_QBUF) failed when requesting new frame! fd: " << fd << " error: " << strerror(errno));
400  }
401 
402  _must_enqueue = false;
403  }
404  }
405 
407  int file_desc,
408  v4l2_buffer v4l_buf,
409  std::shared_ptr<platform::buffer> data_buf
410  )
411  {
412  if (e_max_kernel_buf_type <=buf_type)
413  throw linux_backend_exception("invalid kernel buffer type request");
414 
415  // D457 development - changed from 1 to 0
416  if (file_desc < 0)
417  {
418  // QBUF to be performed by a 3rd party
419  this->buffers.at(buf_type)._managed = true;
420  }
421  else
422  {
423  buffers.at(buf_type)._file_desc = file_desc;
424  buffers.at(buf_type)._managed = false;
425  buffers.at(buf_type)._data_buf = data_buf;
426  buffers.at(buf_type)._dq_buf = v4l_buf;
427  }
428  }
429 
431  {
432  for (auto& buf : buffers)
433  {
434  LOG_DEBUG_V4L("request_next_frame with fd = " << buf._file_desc);
435  if (buf._data_buf && (buf._file_desc >= 0))
436  buf._data_buf->request_next_frame(buf._file_desc);
437  };
438  _md_start = nullptr;
439  _md_size = 0;
440  }
441 
443  {
444  void* md_start = nullptr;
445  auto md_size = 0;
446 
447  if (buffers.at(e_video_buf)._file_desc >=0)
448  {
449  static const int d4xx_md_size = 248;
450  auto buffer = buffers.at(e_video_buf)._data_buf;
451  auto dq = buffers.at(e_video_buf)._dq_buf;
452  auto fr_payload_size = buffer->get_length_frame_only();
453 
454  // For compressed data assume D4XX metadata struct
455  // TODO - devise SKU-agnostic heuristics
456  auto md_appendix_sz = 0L;
457  if (compressed && (dq.bytesused < fr_payload_size))
458  md_appendix_sz = d4xx_md_size;
459  else
460  md_appendix_sz = long(dq.bytesused) - fr_payload_size;
461 
462  if (md_appendix_sz >0 )
463  {
464  md_start = buffer->get_frame_start() + dq.bytesused - md_appendix_sz;
465  md_size = (*(static_cast<uint8_t*>(md_start)));
466  int md_flags = (*(static_cast<uint8_t*>(md_start)+1));
467  // Use heuristics for metadata validation
468  if ((md_appendix_sz != md_size) || (!val_in_range(md_flags, {0x8e, 0x8f})))
469  {
470  md_size = 0;
471  md_start=nullptr;
472  }
473  }
474  }
475 
476  if (nullptr == md_start)
477  {
478  LOG_DEBUG("Could not parse metadata");
479  }
480  set_md_attributes(static_cast<uint8_t>(md_size),md_start);
481  }
482 
484  {
485  if ((buffers[e_video_buf]._file_desc > 0) && (buffers[e_metadata_buf]._file_desc > 0))
486  {
487  if (buffers[e_video_buf]._dq_buf.sequence != buffers[e_metadata_buf]._dq_buf.sequence)
488  {
489  LOG_ERROR("Non-sequential Video and Metadata v4l buffers - video seq = " << buffers[e_video_buf]._dq_buf.sequence << ", md seq = " << buffers[e_metadata_buf]._dq_buf.sequence);
490  return false;
491  }
492  }
493  return true;
494  }
495 
497  {
498  return (buffers[e_metadata_buf]._file_desc > 0);
499  }
500 
501  // retrieve the USB specification attributed to a specific USB device.
502  // This functionality is required to find the USB connection type for UVC device
503  // Note that the input parameter is passed by value
505  {
506  usb_spec res{usb_undefined};
507 
508  char usb_actual_path[PATH_MAX] = {0};
509  if (realpath(path.c_str(), usb_actual_path) != nullptr)
510  {
511  path = std::string(usb_actual_path);
512  std::string camera_usb_version;
513  if(!(std::ifstream(path + "/version") >> camera_usb_version))
514  throw linux_backend_exception("Failed to read usb version specification");
515 
516  // go through the usb_name_to_spec map to find a usb type where the first element is contained in 'camera_usb_version'
517  // (contained and not strictly equal because of differences like "3.2" vs "3.20")
518  for(const auto usb_type : usb_name_to_spec ) {
519  std::string usb_name = usb_type.first;
520  if (std::string::npos != camera_usb_version.find(usb_name))
521  {
522  res = usb_type.second;
523  return res;
524  }
525  }
526  }
527  return res;
528  }
529 
530  // Retrieve device video capabilities to discriminate video capturing and metadata nodes
531  static v4l2_capability get_dev_capabilities(const std::string dev_name)
532  {
533  // RAII to handle exceptions
534  std::unique_ptr<int, std::function<void(int*)> > fd(
535  new int (open(dev_name.c_str(), O_RDWR | O_NONBLOCK, 0)),
536  [](int* d){ if (d && (*d)) {::close(*d); } delete d; });
537 
538  if(*fd < 0)
539  throw linux_backend_exception(rsutils::string::from() << __FUNCTION__ << ": Cannot open '" << dev_name);
540 
541  v4l2_capability cap = {};
542  if(xioctl(*fd, VIDIOC_QUERYCAP, &cap) < 0)
543  {
544  if(errno == EINVAL)
545  throw linux_backend_exception(rsutils::string::from() << __FUNCTION__ << " " << dev_name << " is no V4L2 device");
546  else
547  throw linux_backend_exception(rsutils::string::from() <<__FUNCTION__ << " xioctl(VIDIOC_QUERYCAP) failed");
548  }
549 
550  return cap;
551  }
552 
553  void stream_ctl_on(int fd, v4l2_buf_type type=V4L2_BUF_TYPE_VIDEO_CAPTURE)
554  {
555  if(xioctl(fd, VIDIOC_STREAMON, &type) < 0)
556  throw linux_backend_exception(rsutils::string::from() << "xioctl(VIDIOC_STREAMON) failed for buf_type=" << type);
557  }
558 
559  void stream_off(int fd, v4l2_buf_type type=V4L2_BUF_TYPE_VIDEO_CAPTURE)
560  {
561  if(xioctl(fd, VIDIOC_STREAMOFF, &type) < 0)
562  throw linux_backend_exception(rsutils::string::from() << "xioctl(VIDIOC_STREAMOFF) failed for buf_type=" << type);
563  }
564 
565  void req_io_buff(int fd, uint32_t count, std::string dev_name,
566  v4l2_memory mem_type, v4l2_buf_type type)
567  {
568  struct v4l2_requestbuffers req = { count, type, mem_type, {}};
569 
570  if(xioctl(fd, VIDIOC_REQBUFS, &req) < 0)
571  {
572  if(errno == EINVAL)
573  LOG_ERROR(dev_name + " does not support memory mapping");
574  else
575  return;
576  //D457 - fails on close (when num = 0)
577  //throw linux_backend_exception("xioctl(VIDIOC_REQBUFS) failed");
578  }
579  }
580 
581  bool get_devname_from_video_path(const std::string& video_path, std::string& dev_name)
582  {
583  std::ifstream uevent_file(video_path + "/uevent");
584  if (!uevent_file)
585  {
586  LOG_ERROR("Cannot access " + video_path + "/uevent");
587  return false;
588  }
589 
590  std::string uevent_line, major_string, minor_string;
591  while (std::getline(uevent_file, uevent_line) && (major_string.empty() || minor_string.empty()))
592  {
593  if (uevent_line.find("MAJOR=") != std::string::npos)
594  {
595  major_string = uevent_line.substr(uevent_line.find_last_of('=') + 1);
596  }
597  else if (uevent_line.find("MINOR=") != std::string::npos)
598  {
599  minor_string = uevent_line.substr(uevent_line.find_last_of('=') + 1);
600  }
601  }
602  uevent_file.close();
603 
604  if (major_string.empty() || minor_string.empty())
605  {
606  LOG_ERROR("No Major or Minor number found for " + video_path);
607  return false;
608  }
609 
610  DIR * dir = opendir("/dev");
611  if (!dir)
612  {
613  LOG_ERROR("Cannot access /dev");
614  return false;
615  }
616  while (dirent * entry = readdir(dir))
617  {
618  std::string name = entry->d_name;
619  std::string path = "/dev/" + name;
620 
621  struct stat st = {};
622  if (stat(path.c_str(), &st) < 0)
623  {
624  continue;
625  }
626 
627  if (std::stoi(major_string) == major(st.st_rdev) && std::stoi(minor_string) == minor(st.st_rdev))
628  {
629  dev_name = path;
630  closedir(dir);
631  return true;
632  }
633  }
634  closedir(dir);
635 
636  return false;
637  }
638 
639  std::vector<std::string> v4l_uvc_device::get_video_paths()
640  {
641  std::vector<std::string> video_paths;
642  // Enumerate all subdevices present on the system
643  DIR * dir = opendir("/sys/class/video4linux");
644  if(!dir)
645  {
646  LOG_INFO("Cannot access /sys/class/video4linux");
647  return video_paths;
648  }
649  while (dirent * entry = readdir(dir))
650  {
651  std::string name = entry->d_name;
652  if(name == "." || name == "..") continue;
653 
654  // Resolve a pathname to ignore virtual video devices and sub-devices
655  static const std::regex video_dev_pattern("(\\/video\\d+)$");
656 
657  std::string path = "/sys/class/video4linux/" + name;
658  std::string real_path{};
659  char buff[PATH_MAX] = {0};
660  if (realpath(path.c_str(), buff) != nullptr)
661  {
662  real_path = std::string(buff);
663  if (real_path.find("virtual") != std::string::npos)
664  continue;
665  if (!std::regex_search(real_path, video_dev_pattern))
666  {
667  //LOG_INFO("Skipping Video4Linux entry " << real_path << " - not a device");
668  continue;
669  }
670  if (get_devname_from_video_path(real_path, name))
671  {
672  video_paths.push_back(real_path);
673  }
674  }
675  }
676  closedir(dir);
677 
678 
679  // UVC nodes shall be traversed in ascending order for metadata nodes assignment ("dev/video1, Video2..
680  // Replace lexicographic with numeric sort to ensure "video2" is listed before "video11"
681  std::sort(video_paths.begin(), video_paths.end(),
682  [](const std::string& first, const std::string& second)
683  {
684  // getting videoXX
685  std::string first_video = first.substr(first.find_last_of('/') + 1);
686  std::string second_video = second.substr(second.find_last_of('/') + 1);
687 
688  // getting the index XX from videoXX
689  std::stringstream first_index(first_video.substr(first_video.find_first_of("0123456789")));
690  std::stringstream second_index(second_video.substr(second_video.find_first_of("0123456789")));
691  int left_id = 0, right_id = 0;
692  first_index >> left_id;
693  second_index >> right_id;
694  return left_id < right_id;
695  });
696  return video_paths;
697  }
698 
699  bool v4l_uvc_device::is_usb_path_valid(const std::string& usb_video_path, const std::string& dev_name,
700  std::string& busnum, std::string& devnum, std::string& devpath)
701  {
702  struct stat st = {};
703  if(stat(dev_name.c_str(), &st) < 0)
704  {
705  throw linux_backend_exception(rsutils::string::from() << "Cannot identify '" << dev_name);
706  }
707  if(!S_ISCHR(st.st_mode))
708  throw linux_backend_exception(dev_name + " is no device");
709 
710  // Search directory and up to three parent directories to find busnum/devnum
711  auto valid_path = false;
712  std::ostringstream ss;
713  ss << "/sys/dev/char/" << major(st.st_rdev) << ":" << minor(st.st_rdev) << "/device/";
714 
715  auto char_dev_path = ss.str();
716 
717  for(auto i=0U; i < MAX_DEV_PARENT_DIR; ++i)
718  {
719  if(std::ifstream(char_dev_path + "busnum") >> busnum)
720  {
721  if(std::ifstream(char_dev_path + "devnum") >> devnum)
722  {
723  if(std::ifstream(char_dev_path + "devpath") >> devpath)
724  {
725  valid_path = true;
726  break;
727  }
728  }
729  }
730  char_dev_path += "../";
731  }
732  return valid_path;
733  }
734 
735  uvc_device_info v4l_uvc_device::get_info_from_usb_device_path(const std::string& video_path, const std::string& name)
736  {
737  std::string busnum, devnum, devpath, dev_name;
738  if (!get_devname_from_video_path(video_path, dev_name))
739  {
740  throw linux_backend_exception(rsutils::string::from() << "Unable to find dev_name from video_path: " << video_path);
741  }
742 
743  if (!is_usb_path_valid(video_path, dev_name, busnum, devnum, devpath))
744  {
745 #ifndef RS2_USE_CUDA
746  /* On the Jetson TX, the camera module is CSI & I2C and does not report as this code expects
747  Patch suggested by JetsonHacks: https://github.com/jetsonhacks/buildLibrealsense2TX */
748  LOG_INFO("Failed to read busnum/devnum. Device Path: " << ("/sys/class/video4linux/" + name));
749 #endif
750  throw linux_backend_exception("Failed to read busnum/devnum of usb device");
751  }
752 
753  LOG_INFO("Enumerating UVC " << name << " realpath=" << video_path);
754  uint16_t vid{}, pid{}, mi{};
755  usb_spec usb_specification(usb_undefined);
756 
757  std::string modalias;
758  if(!(std::ifstream("/sys/class/video4linux/" + name + "/device/modalias") >> modalias))
759  throw linux_backend_exception("Failed to read modalias");
760  if(modalias.size() < 14 || modalias.substr(0,5) != "usb:v" || modalias[9] != 'p')
761  throw linux_backend_exception("Not a usb format modalias");
762  if(!(std::istringstream(modalias.substr(5,4)) >> std::hex >> vid))
763  throw linux_backend_exception("Failed to read vendor ID");
764  if(!(std::istringstream(modalias.substr(10,4)) >> std::hex >> pid))
765  throw linux_backend_exception("Failed to read product ID");
766  if(!(std::ifstream("/sys/class/video4linux/" + name + "/device/bInterfaceNumber") >> std::hex >> mi))
767  throw linux_backend_exception("Failed to read interface number");
768 
769  // Find the USB specification (USB2/3) type from the underlying device
770  // Use device mapping obtained in previous step to traverse node tree
771  // and extract the required descriptors
772  // Traverse from
773  // /sys/devices/pci0000:00/0000:00:xx.0/ABC/M-N/3-6:1.0/video4linux/video0
774  // to
775  // /sys/devices/pci0000:00/0000:00:xx.0/ABC/M-N/version
776  usb_specification = get_usb_connection_type(video_path + "/../../../");
777 
779  info.pid = pid;
780  info.vid = vid;
781  info.mi = mi;
782  info.id = dev_name;
783  info.device_path = video_path;
784  info.unique_id = busnum + "-" + devpath + "-" + devnum;
785  info.conn_spec = usb_specification;
786  info.uvc_capabilities = get_dev_capabilities(dev_name).device_caps;
787 
788  return info;
789  }
790 
791  void v4l_uvc_device::get_mipi_device_info(const std::string& dev_name,
792  std::string& bus_info, std::string& card)
793  {
794  struct v4l2_capability vcap;
795  int fd = open(dev_name.c_str(), O_RDWR);
796  if (fd < 0)
797  throw linux_backend_exception("Mipi device capability could not be grabbed");
798  int err = ioctl(fd, VIDIOC_QUERYCAP, &vcap);
799  if (err)
800  {
801  struct media_device_info mdi;
802 
803  err = ioctl(fd, MEDIA_IOC_DEVICE_INFO, &mdi);
804  if (!err)
805  {
806  if (mdi.bus_info[0])
807  bus_info = mdi.bus_info;
808  else
809  bus_info = std::string("platform:") + mdi.driver;
810 
811  if (mdi.model[0])
812  card = mdi.model;
813  else
814  card = mdi.driver;
815  }
816  }
817  else
818  {
819  bus_info = reinterpret_cast<const char *>(vcap.bus_info);
820  card = reinterpret_cast<const char *>(vcap.card);
821  }
822  ::close(fd);
823  }
824 
825  uvc_device_info v4l_uvc_device::get_info_from_mipi_device_path(const std::string& video_path, const std::string& name)
826  {
827  uint16_t vid{}, pid{}, mi{};
828  usb_spec usb_specification(usb_undefined);
829  std::string bus_info, card;
830 
831  auto dev_name = "/dev/" + name;
832 
833  get_mipi_device_info(dev_name, bus_info, card);
834 
835  // the following 2 lines need to be changed in order to enable multiple mipi devices support
836  // or maybe another field in the info structure - TBD
837  vid = 0x8086;
838  pid = 0xABCD; // D457 dev
839 
840  static std::regex video_dev_index("\\d+$");
841  std::smatch match;
842  uint8_t ind{};
843  if (std::regex_search(name, match, video_dev_index))
844  {
845  ind = static_cast<uint8_t>(std::stoi(match[0]));
846  }
847  else
848  {
849  LOG_WARNING("Unresolved Video4Linux device pattern: " << name << ", device is skipped");
850  throw linux_backend_exception("Unresolved Video4Linux device, device is skipped");
851  }
852 
853  // D457 exposes (assuming first_video_index = 0):
854  // - video0 for Depth and video1 for Depth's md.
855  // - video2 for RGB and video3 for RGB's md.
856  // - video4 for IR stream. IR's md is currently not available.
857  // - video5 for IMU (accel or gyro TBD)
858  // next several lines permit to use D457 even if a usb device has already "taken" the video0,1,2 (for example)
859  // further development is needed to permit use of several mipi devices
860  static int first_video_index = ind;
861  // Use camera_video_nodes as number of /dev/video[%d] for each camera sensor subset
862  const int camera_video_nodes = 6;
863  int cam_id = ind / camera_video_nodes;
864  ind = (ind - first_video_index) % camera_video_nodes; // offset from first mipi video node and assume 6 nodes per mipi camera
865  if (ind == 0 || ind == 2 || ind == 4)
866  mi = 0; // video node indicator
867  else if (ind == 1 | ind == 3)
868  mi = 3; // metadata node indicator
869  else if (ind == 5)
870  mi = 4; // IMU node indicator
871  else
872  {
873  LOG_WARNING("Unresolved Video4Linux device mi, device is skipped");
874  throw linux_backend_exception("Unresolved Video4Linux device, device is skipped");
875  }
876 
878  info.pid = pid;
879  info.vid = vid;
880  info.mi = mi;
881  info.id = dev_name;
882  info.device_path = video_path;
883  // unique id for MIPI: This will assign sensor set for each camera.
884  // it cannot be generated as in usb, because the params busnum, devpath and devnum
885  // are not available via mipi
886  // assign unique id for mipi by appending camera id to bus_info (bus_info is same for each mipi port)
887  // Note - jetson can use only bus_info, as card is different for each sensor and metadata node.
888  info.unique_id = bus_info + "-" + std::to_string(cam_id); // use bus_info as per camera unique id for mipi
889  // Get DFU node for MIPI camera
890  std::array<std::string, 2> dfu_device_paths = {"/dev/d4xx-dfu504", "/dev/d4xx-dfu-30-0010"};
891  for (const auto& dfu_device_path: dfu_device_paths) {
892  int vfd = open(dfu_device_path.c_str(), O_RDONLY | O_NONBLOCK);
893  if (vfd >= 0) {
894  // Use legacy DFU device node used in firmware_update_manager
895  info.dfu_device_path = dfu_device_path;
896  ::close(vfd); // file exists, close file and continue to assign it
897  break;
898  }
899  }
900  info.conn_spec = usb_specification;
901  info.uvc_capabilities = get_dev_capabilities(dev_name).device_caps;
902 
903  return info;
904  }
905 
906  bool v4l_uvc_device::is_usb_device_path(const std::string& video_path)
907  {
908  static const std::regex uvc_pattern("(\\/usb\\d+\\/)\\w+"); // Locate UVC device path pattern ../usbX/...
909  return std::regex_search(video_path, uvc_pattern);
910  }
911 
912  void v4l_uvc_device::foreach_uvc_device(
913  std::function<void(const uvc_device_info&,
914  const std::string&)> action)
915  {
916  std::vector<std::string> video_paths = get_video_paths();
917  typedef std::pair<uvc_device_info,std::string> node_info;
918  std::vector<node_info> uvc_nodes,uvc_devices;
919  std::vector<node_info> mipi_rs_enum_nodes;
920  /* Enumerate mipi nodes by links with usage of rs-enum script */
921  std::vector<std::string> video_sensors = {"depth", "color", "ir", "imu"};
922  const int MAX_V4L2_DEVICES = 8; // assume maximum 8 mipi devices
923 
924  for ( int i = 0; i < MAX_V4L2_DEVICES; i++ ) {
925  for (const auto &vs: video_sensors) {
926  int vfd = -1;
927  std::string device_path = "video-rs-" + vs + "-" + std::to_string(i);
928  std::string device_md_path = "video-rs-" + vs + "-md-" + std::to_string(i);
929  std::string video_path = "/dev/" + device_path;
930  std::string video_md_path = "/dev/" + device_md_path;
931  std::string dfu_device_path = "/dev/d4xx-dfu-" + std::to_string(i);
933 
934  // Get Video node
935  // Check if file on video_path is exists
936  vfd = open(video_path.c_str(), O_RDONLY | O_NONBLOCK);
937 
938  if (vfd < 0) // file does not exists, continue to the next one
939  continue;
940  else
941  ::close(vfd); // file exists, close file and continue to assign it
942  try
943  {
944  info = get_info_from_mipi_device_path(video_path, device_path);
945  }
946  catch(const std::exception & e)
947  {
948  LOG_WARNING("MIPI video device issue: " << e.what());
949  continue;
950  }
951 
952  // Get DFU node for MIPI camera
953  vfd = open(dfu_device_path.c_str(), O_RDONLY | O_NONBLOCK);
954 
955  if (vfd >= 0) {
956  ::close(vfd); // file exists, close file and continue to assign it
957  info.dfu_device_path = dfu_device_path;
958  }
959 
960  info.mi = vs.compare("imu") ? 0 : 4;
961  info.unique_id += "-" + std::to_string(i);
962  info.uvc_capabilities &= ~(V4L2_CAP_META_CAPTURE); // clean caps
963  mipi_rs_enum_nodes.emplace_back(info, video_path);
964  // Get metadata node
965  // Check if file on video_md_path is exists
966  vfd = open(video_md_path.c_str(), O_RDONLY | O_NONBLOCK);
967 
968  if (vfd < 0) // file does not exists, continue to the next one
969  continue;
970  else
971  ::close(vfd); // file exists, close file and continue to assign it
972 
973  try
974  {
975  info = get_info_from_mipi_device_path(video_md_path, device_md_path);
976  }
977  catch(const std::exception & e)
978  {
979  LOG_WARNING("MIPI video metadata device issue: " << e.what());
980  continue;
981  }
982  info.mi = 3;
983  info.unique_id += "-" + std::to_string(i);
984  mipi_rs_enum_nodes.emplace_back(info, video_md_path);
985  }
986  }
987 
988  // Append mipi nodes to uvc nodes list
989  if(mipi_rs_enum_nodes.size())
990  {
991  uvc_nodes.insert(uvc_nodes.end(), mipi_rs_enum_nodes.begin(), mipi_rs_enum_nodes.end());
992  }
993 
994  // Collect UVC nodes info to bundle metadata and video
995 
996  for(auto&& video_path : video_paths)
997  {
998  // following line grabs video0 from
999  auto name = video_path.substr(video_path.find_last_of('/') + 1);
1000 
1001  try
1002  {
1004  if (is_usb_device_path(video_path))
1005  {
1006  info = get_info_from_usb_device_path(video_path, name);
1007  }
1008  else if(mipi_rs_enum_nodes.empty()) //video4linux devices that are not USB devices and not previously enumerated by rs links
1009  {
1010  // filter out all posible codecs, work only with compatible driver
1011  static const std::regex rs_mipi_compatible(".vi:|ipu6");
1012  info = get_info_from_mipi_device_path(video_path, name);
1013  if (!regex_search(info.unique_id, rs_mipi_compatible)) {
1014  continue;
1015  }
1016  }
1017  else // continue as we already have mipi nodes enumerated by rs links in uvc_nodes
1018  {
1019  continue;
1020  }
1021 
1022  std::string dev_name;
1023  if (get_devname_from_video_path(video_path, dev_name))
1024  {
1025  uvc_nodes.emplace_back(info, dev_name);
1026  }
1027  }
1028  catch(const std::exception & e)
1029  {
1030  LOG_INFO("Not a USB video device: " << e.what());
1031  }
1032  }
1033 
1034  // Matching video and metadata nodes
1035  // Assume uvc_nodes is already sorted according to videoXX (video0, then video1...)
1036  // Assume for each metadata node with index N there is a origin streaming node with index (N-1)
1037  for (auto&& cur_node : uvc_nodes)
1038  {
1039  try
1040  {
1041  if (!(cur_node.first.uvc_capabilities & V4L2_CAP_META_CAPTURE))
1042  uvc_devices.emplace_back(cur_node);
1043  else
1044  {
1045  if (uvc_devices.empty())
1046  {
1047  LOG_ERROR("UVC meta-node with no video streaming node encountered: " << std::string(cur_node.first));
1048  continue;
1049  }
1050 
1051  // Update the preceding uvc item with metadata node info
1052  auto uvc_node = uvc_devices.back();
1053 
1054  if (uvc_node.first.uvc_capabilities & V4L2_CAP_META_CAPTURE)
1055  {
1056  LOG_ERROR("Consequtive UVC meta-nodes encountered: " << std::string(uvc_node.first) << " and " << std::string(cur_node.first) );
1057  continue;
1058  }
1059 
1060  if (uvc_node.first.has_metadata_node)
1061  {
1062  LOG_ERROR( "Metadata node for uvc device: " << std::string(uvc_node.first) << " was previously assigned ");
1063  continue;
1064  }
1065 
1066  // modify the last element with metadata node info
1067  uvc_node.first.has_metadata_node = true;
1068  uvc_node.first.metadata_node_id = cur_node.first.id;
1069  uvc_devices.back() = uvc_node;
1070  }
1071  }
1072  catch(const std::exception & e)
1073  {
1074  LOG_ERROR("Failed to map meta-node " << std::string(cur_node.first) <<", error encountered: " << e.what());
1075  }
1076  }
1077 
1078  try
1079  {
1080  // Dispatch registration for enumerated uvc devices
1081  for (auto&& dev : uvc_devices)
1082  action(dev.first, dev.second);
1083  }
1084  catch(const std::exception & e)
1085  {
1086  LOG_ERROR("Registration of UVC device failed: " << e.what());
1087  }
1088  }
1089 
1090  bool frame_drop_monitor::update_and_check_kpi(const stream_profile& profile, const timeval& timestamp)
1091  {
1092  bool is_kpi_violated = false;
1093  long int timestamp_usec = static_cast<long int> (timestamp.tv_sec * 1000000 + timestamp.tv_usec);
1094 
1095  // checking if the current profile is already in the drops_per_stream container
1096  auto it = std::find_if(drops_per_stream.begin(), drops_per_stream.end(),
1097  [profile](std::pair<stream_profile, std::deque<long int>>& sp_deq)
1098  {return profile == sp_deq.first; });
1099 
1100  // if the profile is already in the drops_per_stream container,
1101  // checking kpi with the new partial frame caught
1102  if (it != drops_per_stream.end())
1103  {
1104  // setting the kpi checking to be done on the last 30 seconds
1105  int time_limit = 30;
1106 
1107  // max number of drops that can be received in the time_limit, without violation of the kpi
1108  int max_num_of_drops = profile.fps * _kpi_frames_drops_pct * time_limit;
1109 
1110  auto& queue_for_profile = it->second;
1111  // removing too old timestamps of partial frames
1112  while (queue_for_profile.size() > 0)
1113  {
1114  auto delta_ts_usec = timestamp_usec - queue_for_profile.front();
1115  if (delta_ts_usec > (time_limit * 1000000))
1116  {
1117  queue_for_profile.pop_front();
1118  }
1119  else
1120  break; // correct because the frames are added chronologically
1121  }
1122  // checking kpi violation
1123  if (queue_for_profile.size() >= max_num_of_drops)
1124  {
1125  is_kpi_violated = true;
1126  queue_for_profile.clear();
1127  }
1128  else
1129  queue_for_profile.push_back(timestamp_usec);
1130  }
1131  else
1132  {
1133  // adding the the current partial frame's profile and timestamp to the container
1134  std::deque<long int> deque_to_add;
1135  deque_to_add.push_back(timestamp_usec);
1136  drops_per_stream.push_back(std::make_pair(profile, deque_to_add));
1137  }
1138  return is_kpi_violated;
1139  }
1140 
1141  v4l_uvc_device::v4l_uvc_device(const uvc_device_info& info, bool use_memory_map)
1142  : _name(""), _info(),
1143  _is_capturing(false),
1144  _is_alive(true),
1145  _is_started(false),
1146  _thread(nullptr),
1147  _named_mtx(nullptr),
1148  _use_memory_map(use_memory_map),
1149  _fd(-1),
1150  _stop_pipe_fd{},
1151  _buf_dispatch(use_memory_map),
1152  _frame_drop_monitor(DEFAULT_KPI_FRAME_DROPS_PERCENTAGE)
1153  {
1154  foreach_uvc_device([&info, this](const uvc_device_info& i, const std::string& name)
1155  {
1156  if (i == info)
1157  {
1158  _name = name;
1159  _info = i;
1160  _device_path = i.device_path;
1161  _device_usb_spec = i.conn_spec;
1162  }
1163  });
1164  if (_name == "")
1165  throw linux_backend_exception("device is no longer connected!");
1166 
1167  _named_mtx = std::unique_ptr<named_mutex>(new named_mutex(_name, 5000));
1168  }
1169 
1171  {
1172  _is_capturing = false;
1173  if (_thread && _thread->joinable()) _thread->join();
1174  for (auto&& fd : _fds)
1175  {
1176  try { if (fd) ::close(fd);} catch (...) {}
1177  }
1178  }
1179 
1181  {
1182  if(!_is_capturing && !_callback)
1183  {
1184  v4l2_fmtdesc pixel_format = {};
1185  pixel_format.type = _dev.buf_type;
1186 
1187  while (ioctl(_fd, VIDIOC_ENUM_FMT, &pixel_format) == 0)
1188  {
1189  v4l2_frmsizeenum frame_size = {};
1190  frame_size.pixel_format = pixel_format.pixelformat;
1191 
1192  uint32_t fourcc = (const big_endian<int> &)pixel_format.pixelformat;
1193 
1194  if (pixel_format.pixelformat == 0)
1195  {
1196  // Microsoft Depth GUIDs for R400 series are not yet recognized
1197  // by the Linux kernel, but they do not require a patch, since there
1198  // are "backup" Z16 and Y8 formats in place
1199  static const std::set<std::string> pending_formats = {
1200  "00000050-0000-0010-8000-00aa003",
1201  "00000032-0000-0010-8000-00aa003",
1202  };
1203 
1204  if (std::find(pending_formats.begin(),
1205  pending_formats.end(),
1206  (const char*)pixel_format.description) ==
1207  pending_formats.end())
1208  {
1209  const std::string s(rsutils::string::from() << "!" << pixel_format.description);
1210  std::regex rgx("!([0-9a-f]+)-.*");
1211  std::smatch match;
1212 
1213  if (std::regex_search(s.begin(), s.end(), match, rgx))
1214  {
1215  std::stringstream ss;
1216  ss << match[1];
1217  int id;
1218  ss >> std::hex >> id;
1219  fourcc = (const big_endian<int> &)id;
1220 
1221  if (fourcc == profile.format)
1222  {
1223  throw linux_backend_exception(rsutils::string::from() << "The requested pixel format '" << fourcc_to_string(id)
1224  << "' is not natively supported by the running Linux kernel and likely requires a patch");
1225  }
1226  }
1227  }
1228  }
1229  ++pixel_format.index;
1230  }
1231 
1233 
1234  v4l2_streamparm parm = {};
1235  parm.type = _dev.buf_type;
1236  if(xioctl(_fd, VIDIOC_G_PARM, &parm) < 0)
1237  throw linux_backend_exception("xioctl(VIDIOC_G_PARM) failed");
1238 
1239  parm.parm.capture.timeperframe.numerator = 1;
1240  parm.parm.capture.timeperframe.denominator = profile.fps;
1241  if(xioctl(_fd, VIDIOC_S_PARM, &parm) < 0)
1242  throw linux_backend_exception("xioctl(VIDIOC_S_PARM) failed");
1243 
1244  // Init memory mapped IO
1245  negotiate_kernel_buffers(static_cast<size_t>(buffers));
1246  allocate_io_buffers(static_cast<size_t>(buffers));
1247 
1248  _profile = profile;
1249  _callback = callback;
1250  }
1251  else
1252  {
1253  throw wrong_api_call_sequence_exception("Device already streaming!");
1254  }
1255  }
1256 
1257  void v4l_uvc_device::stream_on(std::function<void(const notification& n)> error_handler)
1258  {
1259  if(!_is_capturing)
1260  {
1261  _error_handler = error_handler;
1262 
1263  // Start capturing
1265 
1266  // Synchronise stream requests for meta and video data.
1267  streamon();
1268 
1269  _is_capturing = true;
1270  _thread = std::unique_ptr<std::thread>(new std::thread([this](){ capture_loop(); }));
1271 
1272  // Starting the video/metadata syncer
1274  }
1275  }
1276 
1278  {
1279  for (auto&& buf : _buffers) buf->prepare_for_streaming(_fd);
1280  }
1281 
1283  {
1284  _is_capturing = false;
1285  _is_started = false;
1286 
1287  // Stop nn-demand frames polling
1288  signal_stop();
1289 
1290  _thread->join();
1291  _thread.reset();
1292 
1293  // Notify kernel
1294  streamoff();
1295  }
1296 
1298  {
1299  _is_started = true;
1300  }
1301 
1303  {
1304  _is_started = false;
1305  }
1306 
1308  {
1309  if(_is_capturing)
1310  {
1312  }
1313 
1314  if (_callback)
1315  {
1316  // Release allocated buffers
1318 
1319  // Release IO
1321 
1322  _callback = nullptr;
1323  }
1324  }
1325 
1327  {
1328  uint32_t device_fourcc = id;
1329  char fourcc_buff[sizeof(device_fourcc)+1];
1330  std::memcpy( fourcc_buff, &device_fourcc, sizeof( device_fourcc ) );
1331  fourcc_buff[sizeof(device_fourcc)] = 0;
1332  return fourcc_buff;
1333  }
1334 
1336  {
1338  char buff[1]={};
1339  if (write(_stop_pipe_fd[1], buff, 1) < 0)
1340  {
1341  throw linux_backend_exception("Could not signal video capture thread to stop. Error write to pipe.");
1342  }
1343  }
1344 
1346  {
1347  using namespace std::chrono;
1348 
1349  // get current time
1350  auto now = system_clock::now();
1351 
1352  // get number of milliseconds for the current second
1353  // (remainder after division into seconds)
1354  auto ms = duration_cast<milliseconds>(now.time_since_epoch()) % 1000;
1355 
1356  // convert to std::time_t in order to convert to std::tm (broken time)
1357  auto timer = system_clock::to_time_t(now);
1358 
1359  // convert to broken time
1360  std::tm bt = *std::localtime(&timer);
1361 
1362  std::ostringstream oss;
1363 
1364  oss << std::put_time(&bt, "%H:%M:%S"); // HH:MM:SS
1365  oss << '.' << std::setfill('0') << std::setw(3) << ms.count();
1366  return oss.str();
1367  }
1368 
1370  {
1371  fd_set fds{};
1372  FD_ZERO(&fds);
1373  for (auto fd : _fds)
1374  {
1375  FD_SET(fd, &fds);
1376  }
1377 
1378  struct timespec mono_time;
1379  int ret = clock_gettime(CLOCK_MONOTONIC, &mono_time);
1380  if (ret) throw linux_backend_exception("could not query time!");
1381 
1382  struct timeval expiration_time = { mono_time.tv_sec + 5, mono_time.tv_nsec / 1000 };
1383  int val = 0;
1384 
1385  auto realtime = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch()).count();
1386  auto time_since_epoch = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::steady_clock::now().time_since_epoch()).count();
1387  LOG_DEBUG_V4L("Select initiated at " << time_in_HH_MM_SS_MMM() << ", mono time " << time_since_epoch << ", host time " << realtime );
1388  do {
1389  struct timeval remaining;
1390  ret = clock_gettime(CLOCK_MONOTONIC, &mono_time);
1391  if (ret) throw linux_backend_exception("could not query time!");
1392 
1393  struct timeval current_time = { mono_time.tv_sec, mono_time.tv_nsec / 1000 };
1394  timersub(&expiration_time, &current_time, &remaining);
1395  // timercmp fails cpp check, reduce macro function from time.h
1396 # define timercmp_lt(a, b) \
1397  (((a)->tv_sec == (b)->tv_sec) ? ((a)->tv_usec < (b)->tv_usec) : ((a)->tv_sec < (b)->tv_sec))
1398  if (timercmp_lt(&current_time, &expiration_time)) {
1399  val = select(_max_fd + 1, &fds, nullptr, nullptr, &remaining);
1400  }
1401  else {
1402  val = 0;
1403  LOG_DEBUG_V4L("Select timeouted");
1404  }
1405 
1406  if (val< 0)
1407  LOG_DEBUG_V4L("Select interrupted, val = " << val << ", error = " << errno);
1408  } while (val < 0 && errno == EINTR);
1409 
1410  LOG_DEBUG_V4L("Select done, val = " << val << " at " << time_in_HH_MM_SS_MMM());
1411  if(val < 0)
1412  {
1413  _is_capturing = false;
1414  _is_started = false;
1415 
1416  // Notify kernel
1417  streamoff();
1418  }
1419  else
1420  {
1421  if(val > 0)
1422  {
1423  if(FD_ISSET(_stop_pipe_fd[0], &fds) || FD_ISSET(_stop_pipe_fd[1], &fds))
1424  {
1425  if(!_is_capturing)
1426  {
1427  LOG_INFO("V4L stream is closed");
1428  return;
1429  }
1430  else
1431  {
1432  LOG_ERROR("Stop pipe was signalled during streaming");
1433  return;
1434  }
1435  }
1436  else // Check and acquire data buffers from kernel
1437  {
1438  bool md_extracted = false;
1439  bool keep_md = false;
1440  bool wa_applied = false;
1441  buffers_mgr buf_mgr(_use_memory_map);
1443  {
1444  buf_mgr = _buf_dispatch; // Handle over MD buffer from the previous cycle
1445  md_extracted = true;
1446  wa_applied = true;
1447  _buf_dispatch.set_md_attributes(0,nullptr);
1448  }
1449 
1450  // Relax the required frame size for compressed formats, i.e. MJPG, Z16H
1451  bool compressed_format = val_in_range(_profile.format, { 0x4d4a5047U , 0x5a313648U});
1452 
1453  // METADATA STREAM
1454  // Read metadata. Metadata node performs a blocking call to ensure video and metadata sync
1455  acquire_metadata(buf_mgr,fds,compressed_format);
1456  md_extracted = true;
1457 
1458  if (wa_applied)
1459  {
1460  auto fn = *(uint32_t*)((char*)(buf_mgr.metadata_start())+28);
1461  LOG_DEBUG_V4L("Extracting md buff, fn = " << fn);
1462  }
1463 
1464  // VIDEO STREAM
1465  if(FD_ISSET(_fd, &fds))
1466  {
1467  FD_CLR(_fd,&fds);
1468  v4l2_buffer buf = {};
1469  struct v4l2_plane planes[VIDEO_MAX_PLANES] = {};
1470  buf.type = _dev.buf_type;
1471  buf.memory = _use_memory_map ? V4L2_MEMORY_MMAP : V4L2_MEMORY_USERPTR;
1472  if (_dev.buf_type == V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE) {
1473  buf.m.planes = planes;
1474  buf.length = VIDEO_MAX_PLANES;
1475  }
1476  if(xioctl(_fd, VIDIOC_DQBUF, &buf) < 0)
1477  {
1478  LOG_DEBUG_V4L("Dequeued empty buf for fd " << std::dec << _fd);
1479  }
1480  LOG_DEBUG_V4L("Dequeued buf " << std::dec << buf.index << " for fd " << _fd << " seq " << buf.sequence);
1481  buf.type = _dev.buf_type;
1482  buf.memory = _use_memory_map ? V4L2_MEMORY_MMAP : V4L2_MEMORY_USERPTR;
1483  if (_dev.buf_type == V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE) {
1484  buf.bytesused = buf.m.planes[0].bytesused;
1485  }
1486  auto buffer = _buffers[buf.index];
1487  buf_mgr.handle_buffer(e_video_buf, _fd, buf, buffer);
1488 
1489  if (_is_started)
1490  {
1491  if(buf.bytesused == 0)
1492  {
1493  LOG_DEBUG_V4L("Empty video frame arrived, index " << buf.index);
1494  return;
1495  }
1496 
1497  // Drop partial and overflow frames (assumes D4XX metadata only)
1498  bool partial_frame = (!compressed_format && (buf.bytesused < buffer->get_full_length() - MAX_META_DATA_SIZE));
1499  bool overflow_frame = (buf.bytesused == buffer->get_length_frame_only() + MAX_META_DATA_SIZE);
1500  if (_dev.buf_type == V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE) {
1501  /* metadata size is one line of profile, temporary disable validation */
1502  partial_frame = false;
1503  overflow_frame = false;
1504  }
1505  if (partial_frame || overflow_frame)
1506  {
1507  auto percentage = (100 * buf.bytesused) / buffer->get_full_length();
1508  std::stringstream s;
1509  if (partial_frame)
1510  {
1511  s << "Incomplete video frame detected!\nSize " << buf.bytesused
1512  << " out of " << buffer->get_full_length() << " bytes (" << percentage << "%)";
1513  if (overflow_frame)
1514  {
1515  s << ". Overflow detected: payload size " << buffer->get_length_frame_only();
1516  LOG_ERROR("Corrupted UVC frame data, underflow and overflow reported:\n" << s.str().c_str());
1517  }
1518  }
1519  else
1520  {
1521  if (overflow_frame)
1522  s << "overflow video frame detected!\nSize " << buf.bytesused
1523  << ", payload size " << buffer->get_length_frame_only();
1524  }
1525  LOG_DEBUG("Incomplete frame received: " << s.str()); // Ev -try1
1526  bool kpi_violated = _frame_drop_monitor.update_and_check_kpi(_profile, buf.timestamp);
1527  if (kpi_violated)
1528  {
1530  _error_handler(n);
1531  }
1532 
1533  // Check if metadata was already allocated
1534  if (buf_mgr.metadata_size())
1535  {
1536  LOG_WARNING("Metadata was present when partial frame arrived, mark md as extracted");
1537  md_extracted = true;
1538  LOG_DEBUG_V4L("Discarding md due to invalid video payload");
1539  auto md_buf = buf_mgr.get_buffers().at(e_metadata_buf);
1540  md_buf._data_buf->request_next_frame(md_buf._file_desc,true);
1541  }
1542  }
1543  else
1544  {
1545  if (!_info.has_metadata_node)
1546  {
1547  if(has_metadata())
1548  {
1549  auto timestamp = (double)buf.timestamp.tv_sec*1000.f + (double)buf.timestamp.tv_usec/1000.f;
1551 
1552  // Read metadata. Metadata node performs a blocking call to ensure video and metadata sync
1553  acquire_metadata(buf_mgr,fds,compressed_format);
1554  md_extracted = true;
1555 
1556  if (wa_applied)
1557  {
1558  auto fn = *(uint32_t*)((char*)(buf_mgr.metadata_start())+28);
1559  LOG_DEBUG_V4L("Extracting md buff, fn = " << fn);
1560  }
1561 
1562  auto frame_sz = buf_mgr.md_node_present() ? buf.bytesused :
1563  std::min(buf.bytesused - buf_mgr.metadata_size(), buffer->get_length_frame_only());
1564  frame_object fo{ frame_sz, buf_mgr.metadata_size(),
1566 
1568  buf_mgr.handle_buffer(e_video_buf,-1); // transfer new buffer request to the frame callback
1569 
1570  if (buf_mgr.verify_vd_md_sync())
1571  {
1572  //Invoke user callback and enqueue next frame
1573  _callback(_profile, fo, [buf_mgr]() mutable {
1574  buf_mgr.request_next_frame();
1575  });
1576  }
1577  else
1578  {
1579  LOG_WARNING("Video frame dropped, video and metadata buffers inconsistency");
1580  }
1581  }
1582  else // when metadata is not enabled at all, streaming only video
1583  {
1584  auto timestamp = (double)buf.timestamp.tv_sec * 1000.f + (double)buf.timestamp.tv_usec / 1000.f;
1586 
1587  LOG_DEBUG_V4L("no metadata streamed");
1588  if (buf_mgr.verify_vd_md_sync())
1589  {
1591  buf_mgr.handle_buffer(e_video_buf, -1); // transfer new buffer request to the frame callback
1592 
1593 
1594  auto frame_sz = buf_mgr.md_node_present() ? buf.bytesused :
1595  std::min(buf.bytesused - buf_mgr.metadata_size(),
1597 
1598  uint8_t md_size = buf_mgr.metadata_size();
1599  void* md_start = buf_mgr.metadata_start();
1600 
1601  // D457 development - hid over uvc - md size for IMU is 64
1602  metadata_hid_raw meta_data{};
1603  if (md_size == 0 && buffer->get_length_frame_only() <= 64)
1604  {
1605  // Populate HID IMU data - Header
1606  populate_imu_data(meta_data, buffer->get_frame_start(), md_size, &md_start);
1607  }
1608 
1609  frame_object fo{ frame_sz, md_size,
1610  buffer->get_frame_start(), md_start, timestamp };
1611 
1612  //Invoke user callback and enqueue next frame
1613  _callback(_profile, fo, [buf_mgr]() mutable {
1614  buf_mgr.request_next_frame();
1615  });
1616  }
1617  else
1618  {
1619  LOG_WARNING("Video frame dropped, video and metadata buffers inconsistency");
1620  }
1621  }
1622  }
1623  else
1624  {
1625  // saving video buffer to syncer
1626  _video_md_syncer.push_video({std::make_shared<v4l2_buffer>(buf), _fd, buf.index});
1627  buf_mgr.handle_buffer(e_video_buf, -1);
1628  }
1629  }
1630  }
1631  else
1632  {
1633  LOG_DEBUG_V4L("Video frame arrived in idle mode."); // TODO - verification
1634  }
1635  }
1636  else
1637  {
1638  if (_is_started)
1639  keep_md = true;
1640  LOG_DEBUG("FD_ISSET: no data on video node sink");
1641  }
1642 
1643  // pulling synchronized video and metadata and uploading them to user's callback
1645  }
1646  }
1647  else // (val==0)
1648  {
1649  LOG_WARNING("Frames didn't arrived within 5 seconds");
1650  librealsense::notification n = {RS2_NOTIFICATION_CATEGORY_FRAMES_TIMEOUT, 0, RS2_LOG_SEVERITY_WARN, "Frames didn't arrived within 5 seconds"};
1651 
1652  _error_handler(n);
1653  }
1654  }
1655  }
1656 
1657  void v4l_uvc_device::populate_imu_data(metadata_hid_raw& meta_data, uint8_t* frame_start, uint8_t& md_size, void** md_start) const
1658  {
1661  meta_data.header.timestamp = *(reinterpret_cast<uint64_t *>(frame_start + offsetof(hid_mipi_data, hwTs)));
1662  // Payload:
1665 
1666  md_size = sizeof(metadata_hid_raw);
1667  *md_start = &meta_data;
1668  }
1669 
1670 
1672  {
1673  // uploading to user's callback
1674  std::shared_ptr<v4l2_buffer> video_v4l2_buffer;
1675  std::shared_ptr<v4l2_buffer> md_v4l2_buffer;
1676 
1678  {
1679  int video_fd = -1, md_fd = -1;
1680  if (_video_md_syncer.pull_video_with_metadata(video_v4l2_buffer, md_v4l2_buffer, video_fd, md_fd))
1681  {
1682  // Preparing video buffer
1683  auto video_buffer = get_video_buffer(video_v4l2_buffer->index);
1684  video_buffer->attach_buffer(*video_v4l2_buffer);
1685 
1686  // happens when the video did not arrive on
1687  // the current polling iteration (was taken from the syncer's video queue)
1688  if (buf_mgr.get_buffers()[e_video_buf]._file_desc == -1)
1689  {
1690  buf_mgr.handle_buffer(e_video_buf, video_fd, *video_v4l2_buffer, video_buffer);
1691  }
1692  buf_mgr.handle_buffer(e_video_buf, -1); // transfer new buffer request to the frame callback
1693 
1694  // Preparing metadata buffer
1695  auto metadata_buffer = get_md_buffer(md_v4l2_buffer->index);
1696  set_metadata_attributes(buf_mgr, md_v4l2_buffer->bytesused, metadata_buffer->get_frame_start());
1697  metadata_buffer->attach_buffer(*md_v4l2_buffer);
1698 
1699  if (buf_mgr.get_buffers()[e_metadata_buf]._file_desc == -1)
1700  {
1701  buf_mgr.handle_buffer(e_metadata_buf, md_fd, *md_v4l2_buffer, metadata_buffer);
1702  }
1703  buf_mgr.handle_buffer(e_metadata_buf, -1); // transfer new buffer request to the frame callback
1704 
1705  auto frame_sz = buf_mgr.md_node_present() ? video_v4l2_buffer->bytesused :
1706  std::min(video_v4l2_buffer->bytesused - buf_mgr.metadata_size(),
1707  video_buffer->get_length_frame_only());
1708 
1709  auto timestamp = (double)video_v4l2_buffer->timestamp.tv_sec * 1000.f + (double)video_v4l2_buffer->timestamp.tv_usec / 1000.f;
1711 
1712  // D457 work - to work with "normal camera", use frame_sz as the first input to the following frame_object:
1713  //frame_object fo{ buf.bytesused - MAX_META_DATA_SIZE, buf_mgr.metadata_size(),
1714  frame_object fo{ frame_sz, buf_mgr.metadata_size(),
1715  video_buffer->get_frame_start(), buf_mgr.metadata_start(), timestamp };
1716 
1717  //Invoke user callback and enqueue next frame
1718  _callback(_profile, fo, [buf_mgr]() mutable {
1719  buf_mgr.request_next_frame();
1720  });
1721  }
1722  else
1723  {
1724  LOG_DEBUG("video_md_syncer - synchronized video and md could not be pulled");
1725  }
1726  }
1727  }
1728 
1729  void v4l_uvc_device::set_metadata_attributes(buffers_mgr& buf_mgr, __u32 bytesused, uint8_t* md_start)
1730  {
1731  size_t uvc_md_start_offset = sizeof(uvc_meta_buffer::ns) + sizeof(uvc_meta_buffer::sof);
1732  buf_mgr.set_md_attributes(bytesused - uvc_md_start_offset,
1733  md_start + uvc_md_start_offset);
1734  }
1735 
1736  void v4l_mipi_device::set_metadata_attributes(buffers_mgr& buf_mgr, __u32 bytesused, uint8_t* md_start)
1737  {
1738  buf_mgr.set_md_attributes(bytesused, md_start);
1739  }
1740 
1742  {
1743  v4l2_capability cap = get_dev_capabilities(_name);
1744 
1745  std::string driver_str = reinterpret_cast<char*>(cap.driver);
1746  // checking if "tegra" is part of the driver string
1747  size_t pos = driver_str.find("tegra");
1748  return pos != std::string::npos;
1749  }
1750 
1751  void v4l_uvc_device::acquire_metadata(buffers_mgr& buf_mgr,fd_set &, bool compressed_format)
1752  {
1753  if (has_metadata())
1754  buf_mgr.set_md_from_video_node(compressed_format);
1755  else
1756  buf_mgr.set_md_attributes(0, nullptr);
1757  }
1758 
1760  {
1761  if (state == D0 && _state == D3)
1762  {
1764  }
1765  if (state == D3 && _state == D0)
1766  {
1767  close(_profile);
1769  }
1770  _state = state;
1771  }
1772 
1774  {
1775  uvc_xu_control_query q = {static_cast<uint8_t>(xu.unit), control, UVC_SET_CUR,
1776  static_cast<uint16_t>(size), const_cast<uint8_t *>(data)};
1777  if(xioctl(_fd, UVCIOC_CTRL_QUERY, &q) < 0)
1778  {
1779  if (errno == EIO || errno == EAGAIN || errno == EBUSY)
1780  return false;
1781 
1782  throw linux_backend_exception("set_xu(...). xioctl(UVCIOC_CTRL_QUERY) failed");
1783  }
1784 
1785  return true;
1786  }
1788  {
1789  memset(data, 0, size);
1790  uvc_xu_control_query q = {static_cast<uint8_t>(xu.unit), control, UVC_GET_CUR,
1791  static_cast<uint16_t>(size), const_cast<uint8_t *>(data)};
1792  if(xioctl(_fd, UVCIOC_CTRL_QUERY, &q) < 0)
1793  {
1794  if (errno == EIO || errno == EAGAIN || errno == EBUSY)
1795  return false;
1796 
1797  throw linux_backend_exception("get_xu(...). xioctl(UVCIOC_CTRL_QUERY) failed");
1798  }
1799 
1800  return true;
1801  }
1803  {
1805  __u16 size = 0;
1806  //__u32 value = 0; // all of the real sense extended controls are up to 4 bytes
1807  // checking return value for UVC_GET_LEN and allocating
1808  // appropriately might be better
1809  //__u8 * data = (__u8 *)&value;
1810  // MS XU controls are partially supported only
1811  struct uvc_xu_control_query xquery = {};
1812  memset(&xquery, 0, sizeof(xquery));
1813  xquery.query = UVC_GET_LEN;
1814  xquery.size = 2; // size seems to always be 2 for the LEN query, but
1815  //doesn't seem to be documented. Use result for size
1816  //in all future queries of the same control number
1817  xquery.selector = control;
1818  xquery.unit = xu.unit;
1819  xquery.data = (__u8 *)&size;
1820 
1821  if(-1 == ioctl(_fd,UVCIOC_CTRL_QUERY,&xquery)){
1822  throw linux_backend_exception("xioctl(UVC_GET_LEN) failed");
1823  }
1824 
1825  assert(size<=len);
1826 
1827  std::vector<uint8_t> buf;
1828  auto buf_size = std::max((size_t)len,sizeof(__u32));
1829  buf.resize(buf_size);
1830 
1831  xquery.query = UVC_GET_MIN;
1832  xquery.size = size;
1833  xquery.selector = control;
1834  xquery.unit = xu.unit;
1835  xquery.data = buf.data();
1836  if(-1 == ioctl(_fd,UVCIOC_CTRL_QUERY,&xquery)){
1837  throw linux_backend_exception("xioctl(UVC_GET_MIN) failed");
1838  }
1839  result.min.resize(buf_size);
1840  std::copy(buf.begin(), buf.end(), result.min.begin());
1841 
1842  xquery.query = UVC_GET_MAX;
1843  xquery.size = size;
1844  xquery.selector = control;
1845  xquery.unit = xu.unit;
1846  xquery.data = buf.data();
1847  if(-1 == ioctl(_fd,UVCIOC_CTRL_QUERY,&xquery)){
1848  throw linux_backend_exception("xioctl(UVC_GET_MAX) failed");
1849  }
1850  result.max.resize(buf_size);
1851  std::copy(buf.begin(), buf.end(), result.max.begin());
1852 
1853  xquery.query = UVC_GET_DEF;
1854  xquery.size = size;
1855  xquery.selector = control;
1856  xquery.unit = xu.unit;
1857  xquery.data = buf.data();
1858  if(-1 == ioctl(_fd,UVCIOC_CTRL_QUERY,&xquery)){
1859  throw linux_backend_exception("xioctl(UVC_GET_DEF) failed");
1860  }
1861  result.def.resize(buf_size);
1862  std::copy(buf.begin(), buf.end(), result.def.begin());
1863 
1864  xquery.query = UVC_GET_RES;
1865  xquery.size = size;
1866  xquery.selector = control;
1867  xquery.unit = xu.unit;
1868  xquery.data = buf.data();
1869  if(-1 == ioctl(_fd,UVCIOC_CTRL_QUERY,&xquery)){
1870  throw linux_backend_exception("xioctl(UVC_GET_CUR) failed");
1871  }
1872  result.step.resize(buf_size);
1873  std::copy(buf.begin(), buf.end(), result.step.begin());
1874 
1875  return result;
1876  }
1877 
1879  {
1880  struct v4l2_control control = {get_cid(opt), 0};
1881  if (xioctl(_fd, VIDIOC_G_CTRL, &control) < 0)
1882  {
1883  if (errno == EIO || errno == EAGAIN || errno == EBUSY)
1884  return false;
1885 
1886  throw linux_backend_exception("xioctl(VIDIOC_G_CTRL) failed");
1887  }
1888 
1889  if (RS2_OPTION_ENABLE_AUTO_EXPOSURE==opt) { control.value = (V4L2_EXPOSURE_MANUAL==control.value) ? 0 : 1; }
1890  value = control.value;
1891 
1892  return true;
1893  }
1894 
1896  {
1897  struct v4l2_control control = {get_cid(opt), value};
1898  if (RS2_OPTION_ENABLE_AUTO_EXPOSURE==opt) { control.value = value ? V4L2_EXPOSURE_APERTURE_PRIORITY : V4L2_EXPOSURE_MANUAL; }
1899 
1900  // We chose not to protect the subscribe / unsubscribe with mutex due to performance reasons,
1901  // we prefer returning on timeout (and let the retry mechanism try again if exist) than blocking the main thread on every set command
1902 
1903 
1904  // RAII to handle unsubscribe in case of exceptions
1905  std::unique_ptr< uint32_t, std::function< void( uint32_t * ) > > unsubscriber(
1906  new uint32_t( control.id ),
1907  [this]( uint32_t * id ) {
1908  if (id)
1909  {
1910  // `unsubscribe_from_ctrl_event()` may throw so we first release the memory allocated and than call it.
1911  auto local_id = *id;
1912  delete id;
1913  unsubscribe_from_ctrl_event( local_id );
1914  }
1915  } );
1916 
1917  subscribe_to_ctrl_event(control.id);
1918 
1919  // Set value
1920  if (xioctl(_fd, VIDIOC_S_CTRL, &control) < 0)
1921  {
1922  if (errno == EIO || errno == EAGAIN || errno == EBUSY)
1923  return false;
1924 
1925  throw linux_backend_exception("xioctl(VIDIOC_S_CTRL) failed");
1926  }
1927 
1928  if (!pend_for_ctrl_status_event())
1929  return false;
1930 
1931  return true;
1932  }
1933 
1935  {
1936  // Auto controls range is trimed to {0,1} range
1938  {
1939  static const int32_t min = 0, max = 1, step = 1, def = 1;
1940  control_range range(min, max, step, def);
1941 
1942  return range;
1943  }
1944 
1945  struct v4l2_queryctrl query = {};
1946  query.id = get_cid(option);
1947  if (xioctl(_fd, VIDIOC_QUERYCTRL, &query) < 0)
1948  {
1949  // Some controls (exposure, auto exposure, auto hue) do not seem to work on V4L2
1950  // Instead of throwing an error, return an empty range. This will cause this control to be omitted on our UI sample.
1951  // TODO: Figure out what can be done about these options and make this work
1952  query.minimum = query.maximum = 0;
1953  }
1954 
1955  control_range range(query.minimum, query.maximum, query.step, query.default_value);
1956 
1957  return range;
1958  }
1959 
1960  std::vector<stream_profile> v4l_uvc_device::get_profiles() const
1961  {
1962  std::vector<stream_profile> results;
1963 
1964  // Retrieve the caps one by one, first get pixel format, then sizes, then
1965  // frame rates. See http://linuxtv.org/downloads/v4l-dvb-apis for reference.
1966  v4l2_fmtdesc pixel_format = {};
1967  pixel_format.type = _dev.buf_type;
1968  while (ioctl(_fd, VIDIOC_ENUM_FMT, &pixel_format) == 0)
1969  {
1970  v4l2_frmsizeenum frame_size = {};
1971  frame_size.pixel_format = pixel_format.pixelformat;
1972 
1973  uint32_t fourcc = (const big_endian<int> &)pixel_format.pixelformat;
1974 
1975  if (pixel_format.pixelformat == 0)
1976  {
1977  // Microsoft Depth GUIDs for R400 series are not yet recognized
1978  // by the Linux kernel, but they do not require a patch, since there
1979  // are "backup" Z16 and Y8 formats in place
1980  std::set<std::string> known_problematic_formats = {
1981  "00000050-0000-0010-8000-00aa003",
1982  "00000032-0000-0010-8000-00aa003",
1983  };
1984 
1985  if (std::find(known_problematic_formats.begin(),
1986  known_problematic_formats.end(),
1987  (const char*)pixel_format.description) ==
1988  known_problematic_formats.end())
1989  {
1990  const std::string s(rsutils::string::from() << "!" << pixel_format.description);
1991  std::regex rgx("!([0-9a-f]+)-.*");
1992  std::smatch match;
1993 
1994  if (std::regex_search(s.begin(), s.end(), match, rgx))
1995  {
1996  std::stringstream ss;
1997  ss << match[1];
1998  int id;
1999  ss >> std::hex >> id;
2000  fourcc = (const big_endian<int> &)id;
2001 
2002  auto format_str = fourcc_to_string(id);
2003  LOG_WARNING("Pixel format " << pixel_format.description << " likely requires patch for fourcc code " << format_str << "!");
2004  }
2005  }
2006  }
2007  else
2008  {
2009  LOG_DEBUG("Recognized pixel-format " << pixel_format.description);
2010  }
2011 
2012  while (ioctl(_fd, VIDIOC_ENUM_FRAMESIZES, &frame_size) == 0)
2013  {
2014  v4l2_frmivalenum frame_interval = {};
2015  frame_interval.pixel_format = pixel_format.pixelformat;
2016  frame_interval.width = frame_size.discrete.width;
2017  frame_interval.height = frame_size.discrete.height;
2018  while (ioctl(_fd, VIDIOC_ENUM_FRAMEINTERVALS, &frame_interval) == 0)
2019  {
2020  if (frame_interval.type == V4L2_FRMIVAL_TYPE_DISCRETE)
2021  {
2022  if (frame_interval.discrete.numerator != 0)
2023  {
2024  auto fps =
2025  static_cast<float>(frame_interval.discrete.denominator) /
2026  static_cast<float>(frame_interval.discrete.numerator);
2027 
2028  stream_profile p{};
2029  p.format = fourcc;
2030  p.width = frame_size.discrete.width;
2031  p.height = frame_size.discrete.height;
2032  p.fps = fps;
2033  if (fourcc != 0) results.push_back(p);
2034  }
2035  }
2036 
2037  ++frame_interval.index;
2038  }
2039 
2040  ++frame_size.index;
2041  }
2042 
2043  ++pixel_format.index;
2044  }
2045  return results;
2046  }
2047 
2049  {
2050  _named_mtx->lock();
2051  }
2053  {
2054  _named_mtx->unlock();
2055  }
2056 
2058  {
2059  switch(option)
2060  {
2061  case RS2_OPTION_BACKLIGHT_COMPENSATION: return V4L2_CID_BACKLIGHT_COMPENSATION;
2062  case RS2_OPTION_BRIGHTNESS: return V4L2_CID_BRIGHTNESS;
2063  case RS2_OPTION_CONTRAST: return V4L2_CID_CONTRAST;
2064  case RS2_OPTION_EXPOSURE: return V4L2_CID_EXPOSURE_ABSOLUTE; // Is this actually valid? I'm getting a lot of VIDIOC error 22s...
2065  case RS2_OPTION_GAIN: return V4L2_CID_GAIN;
2066  case RS2_OPTION_GAMMA: return V4L2_CID_GAMMA;
2067  case RS2_OPTION_HUE: return V4L2_CID_HUE;
2068  case RS2_OPTION_SATURATION: return V4L2_CID_SATURATION;
2069  case RS2_OPTION_SHARPNESS: return V4L2_CID_SHARPNESS;
2070  case RS2_OPTION_WHITE_BALANCE: return V4L2_CID_WHITE_BALANCE_TEMPERATURE;
2071  case RS2_OPTION_ENABLE_AUTO_EXPOSURE: return V4L2_CID_EXPOSURE_AUTO; // Automatic gain/exposure control
2072  case RS2_OPTION_ENABLE_AUTO_WHITE_BALANCE: return V4L2_CID_AUTO_WHITE_BALANCE;
2073  case RS2_OPTION_POWER_LINE_FREQUENCY : return V4L2_CID_POWER_LINE_FREQUENCY;
2074  case RS2_OPTION_AUTO_EXPOSURE_PRIORITY: return V4L2_CID_EXPOSURE_AUTO_PRIORITY;
2075  default: throw linux_backend_exception(rsutils::string::from() << "no v4l2 cid for option " << option);
2076  }
2077  }
2078 
2080  {
2081  try
2082  {
2083  while(_is_capturing)
2084  {
2085  poll();
2086  }
2087  }
2088  catch (const std::exception& ex)
2089  {
2090  LOG_ERROR(ex.what());
2091 
2093 
2094  _error_handler(n);
2095  }
2096  }
2097 
2099  {
2100  return !_use_memory_map;
2101  }
2102 
2104  {
2106  }
2107 
2109  {
2111  }
2112 
2114  {
2116  _use_memory_map ? V4L2_MEMORY_MMAP : V4L2_MEMORY_USERPTR,
2117  _dev.buf_type);
2118  }
2119 
2121  {
2122  if (buffers)
2123  {
2124  for(size_t i = 0; i < buffers; ++i)
2125  {
2126  _buffers.push_back(std::make_shared<buffer>(_fd, _dev.buf_type, _use_memory_map, i));
2127  }
2128  }
2129  else
2130  {
2131  for(size_t i = 0; i < _buffers.size(); i++)
2132  {
2133  _buffers[i]->detach_buffer();
2134  }
2135  _buffers.resize(0);
2136  }
2137  }
2138 
2140  {
2141  _fd = open(_name.c_str(), O_RDWR | O_NONBLOCK, 0);
2142  if(_fd < 0)
2143  throw linux_backend_exception(rsutils::string::from() <<__FUNCTION__ << " Cannot open '" << _name);
2144 
2145  if (pipe(_stop_pipe_fd) < 0)
2146  throw linux_backend_exception(rsutils::string::from() <<__FUNCTION__ << " Cannot create pipe!");
2147 
2148  if (_fds.size())
2149  throw linux_backend_exception(rsutils::string::from() <<__FUNCTION__ << " Device descriptor is already allocated");
2150 
2151  _fds.insert(_fds.end(),{_fd,_stop_pipe_fd[0],_stop_pipe_fd[1]});
2152  _max_fd = *std::max_element(_fds.begin(),_fds.end());
2153 
2154  v4l2_capability cap = {};
2155  if(xioctl(_fd, VIDIOC_QUERYCAP, &cap) < 0)
2156  {
2157  if(errno == EINVAL)
2158  throw linux_backend_exception(_name + " is not V4L2 device");
2159  else
2160  throw linux_backend_exception("xioctl(VIDIOC_QUERYCAP) failed");
2161  }
2162  if(!(cap.capabilities & (V4L2_CAP_VIDEO_CAPTURE_MPLANE | V4L2_CAP_VIDEO_CAPTURE)))
2163  throw linux_backend_exception(_name + " is no video capture device");
2164 
2165  if(!(cap.capabilities & V4L2_CAP_STREAMING))
2166  throw linux_backend_exception(_name + " does not support streaming I/O");
2167  _info.uvc_capabilities = cap.capabilities;
2168  _dev.cap = cap;
2169  /* supporting only one plane for IPU6 */
2170  _dev.num_planes = 1;
2171  if (cap.capabilities & V4L2_CAP_VIDEO_CAPTURE) {
2172  _dev.buf_type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
2173  } else if (cap.capabilities & V4L2_CAP_VIDEO_CAPTURE_MPLANE) {
2174  _dev.buf_type = V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE;
2175  } else {
2176  throw linux_backend_exception(_name + " Buffer type is unknown!");
2177  }
2178  // Select video input, video standard and tune here.
2179  v4l2_cropcap cropcap = {};
2180  cropcap.type = _dev.buf_type;
2181  if(xioctl(_fd, VIDIOC_CROPCAP, &cropcap) == 0)
2182  {
2183  v4l2_crop crop = {};
2184  crop.type = _dev.buf_type;
2185  crop.c = cropcap.defrect; // reset to default
2186  if(xioctl(_fd, VIDIOC_S_CROP, &crop) < 0)
2187  {
2188  switch (errno)
2189  {
2190  case EINVAL: break; // Cropping not supported
2191  default: break; // Errors ignored
2192  }
2193  }
2194  _dev.cropcap = cropcap;
2195  } else {} // Errors ignored
2196  }
2197 
2199  {
2200  if(::close(_fd) < 0)
2201  throw linux_backend_exception("v4l_uvc_device: close(_fd) failed");
2202 
2203  if(::close(_stop_pipe_fd[0]) < 0)
2204  throw linux_backend_exception("v4l_uvc_device: close(_stop_pipe_fd[0]) failed");
2205  if(::close(_stop_pipe_fd[1]) < 0)
2206  throw linux_backend_exception("v4l_uvc_device: close(_stop_pipe_fd[1]) failed");
2207 
2208  _fd = 0;
2209  _stop_pipe_fd[0] = _stop_pipe_fd[1] = 0;
2210  _fds.clear();
2211  }
2212 
2214  {
2215  v4l2_format fmt = {};
2216  fmt.type = _dev.buf_type;
2217  if (_dev.buf_type == V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE) {
2218  fmt.fmt.pix_mp.width = profile.width;
2219  fmt.fmt.pix_mp.height = profile.height;
2220  fmt.fmt.pix_mp.pixelformat = (const big_endian<int> &)profile.format;
2221  fmt.fmt.pix_mp.field = V4L2_FIELD_NONE;
2222  fmt.fmt.pix_mp.num_planes = _dev.num_planes;
2223  fmt.fmt.pix_mp.flags = 0;
2224 
2225  for (int i = 0; i < fmt.fmt.pix_mp.num_planes; i++) {
2226  fmt.fmt.pix_mp.plane_fmt[i].bytesperline = 0;
2227  fmt.fmt.pix_mp.plane_fmt[i].sizeimage = 0;
2228  }
2229  } else {
2230  fmt.fmt.pix.width = profile.width;
2231  fmt.fmt.pix.height = profile.height;
2232  fmt.fmt.pix.pixelformat = (const big_endian<int> &)profile.format;
2233  fmt.fmt.pix.field = V4L2_FIELD_NONE;
2234  }
2235  if(xioctl(_fd, VIDIOC_S_FMT, &fmt) < 0)
2236  {
2237  throw linux_backend_exception(rsutils::string::from() << "xioctl(VIDIOC_S_FMT) failed, errno=" << errno);
2238  }
2239  else
2240  LOG_INFO("Video node was successfully configured to " << fourcc_to_string(fmt.fmt.pix.pixelformat) << " format" <<", fd " << std::dec << _fd);
2241 
2242  LOG_INFO("Trying to configure fourcc " << fourcc_to_string(fmt.fmt.pix.pixelformat));
2243  }
2244 
2246  {
2247  struct v4l2_event_subscription event_subscription ;
2248  event_subscription.flags = V4L2_EVENT_SUB_FL_ALLOW_FEEDBACK;
2249  event_subscription.type = V4L2_EVENT_CTRL;
2250  event_subscription.id = control_id;
2251  memset(event_subscription.reserved,0, sizeof(event_subscription.reserved));
2252  if (xioctl(_fd, VIDIOC_SUBSCRIBE_EVENT, &event_subscription) < 0)
2253  {
2254  throw linux_backend_exception(rsutils::string::from() << "xioctl(VIDIOC_SUBSCRIBE_EVENT) with control_id = " << control_id << " failed");
2255  }
2256  }
2257 
2259  {
2260  struct v4l2_event_subscription event_subscription ;
2261  event_subscription.flags = V4L2_EVENT_SUB_FL_ALLOW_FEEDBACK;
2262  event_subscription.type = V4L2_EVENT_CTRL;
2263  event_subscription.id = control_id;
2264  memset(event_subscription.reserved,0, sizeof(event_subscription.reserved));
2265  if (xioctl(_fd, VIDIOC_UNSUBSCRIBE_EVENT, &event_subscription) < 0)
2266  {
2267  throw linux_backend_exception(rsutils::string::from() << "xioctl(VIDIOC_UNSUBSCRIBE_EVENT) with control_id = " << control_id << " failed");
2268  }
2269  }
2270 
2271 
2273  {
2274  struct v4l2_event event;
2275  memset(&event, 0 , sizeof(event));
2276 
2277  // Poll registered events and verify that set control event raised (wait max of 10 * 2 = 20 [ms])
2278  static int MAX_POLL_RETRIES = 10;
2279  for ( int i = 0 ; i < MAX_POLL_RETRIES && event.type != V4L2_EVENT_CTRL ; i++)
2280  {
2281  if(xioctl(_fd, VIDIOC_DQEVENT, &event) < 0)
2282  {
2283  std::this_thread::sleep_for(std::chrono::milliseconds(2));
2284  }
2285  }
2286 
2287  return event.type == V4L2_EVENT_CTRL;
2288  }
2289 
2291  v4l_uvc_device(info,use_memory_map),
2292  _md_fd(0),
2293  _md_name(info.metadata_node_id)
2294  {
2295  }
2296 
2298  {
2299  }
2300 
2302  {
2303  bool jetson_platform = is_platform_jetson();
2304  if ((_md_fd != -1) && jetson_platform)
2305  {
2306  // D457 development - added for mipi device, for IR because no metadata there
2307  // Metadata stream shall be configured first to allow sync with video node
2309  }
2310 
2311  // Invoke UVC streaming request
2313 
2314  // Metadata stream configured last for IPU6 and it will be in sync with video node
2315  if ((_md_fd != -1) && !jetson_platform)
2316  {
2318  }
2319 
2320  }
2321 
2323  {
2324  bool jetson_platform = is_platform_jetson();
2325  // IPU6 platform should stop md, then video
2326  if (jetson_platform)
2328 
2329  if (_md_fd != -1)
2330  {
2331  // D457 development - added for mipi device, for IR because no metadata there
2333  }
2334  if (!jetson_platform)
2336  }
2337 
2339  {
2341 
2342  if (_md_fd == -1)
2343  {
2344  // D457 development - added for mipi device, for IR because no metadata there
2345  return;
2346  }
2348  _use_memory_map ? V4L2_MEMORY_MMAP : V4L2_MEMORY_USERPTR,
2349  _md_type);
2350  }
2351 
2353  {
2355 
2356  if (buffers)
2357  {
2358  for(size_t i = 0; i < buffers; ++i)
2359  {
2360  // D457 development - added for mipi device, for IR because no metadata there
2361  if (_md_fd == -1)
2362  continue;
2363  _md_buffers.push_back(std::make_shared<buffer>(_md_fd, _md_type, _use_memory_map, i));
2364  }
2365  }
2366  else
2367  {
2368  for(size_t i = 0; i < _md_buffers.size(); i++)
2369  {
2370  _md_buffers[i]->detach_buffer();
2371  }
2372  _md_buffers.resize(0);
2373  }
2374  }
2375 
2377  {
2379 
2380  if (_md_fd>0)
2381  throw linux_backend_exception(rsutils::string::from() << _md_name << " descriptor is already opened");
2382 
2383  _md_fd = open(_md_name.c_str(), O_RDWR | O_NONBLOCK, 0);
2384  if(_md_fd < 0)
2385  {
2386  return; // Does not throw, MIPI device metadata not received through UVC, no metadata here may be valid
2387  }
2388 
2389  //The minimal video/metadata nodes syncer will be implemented by using two blocking calls:
2390  // 1. Obtain video node data.
2391  // 2. Obtain metadata
2392  // To revert to multiplexing mode uncomment the next line
2393  _fds.push_back(_md_fd);
2394  _max_fd = *std::max_element(_fds.begin(),_fds.end());
2395 
2396  v4l2_capability cap = {};
2397  if(xioctl(_md_fd, VIDIOC_QUERYCAP, &cap) < 0)
2398  {
2399  if(errno == EINVAL)
2400  throw linux_backend_exception(_md_name + " is no V4L2 device");
2401  else
2402  throw linux_backend_exception(_md_name + " xioctl(VIDIOC_QUERYCAP) for metadata failed");
2403  }
2404 
2405  if(!(cap.capabilities & V4L2_CAP_META_CAPTURE))
2406  throw linux_backend_exception(_md_name + " is not metadata capture device");
2407 
2408  if(!(cap.capabilities & V4L2_CAP_STREAMING))
2409  throw linux_backend_exception(_md_name + " does not support metadata streaming I/O");
2410 
2411  if(cap.capabilities & V4L2_CAP_META_CAPTURE)
2413  }
2414 
2415 
2417  {
2419 
2420  if(::close(_md_fd) < 0)
2421  {
2422  return; // Does not throw, MIPI device metadata not received through UVC, no metadata here may be valid
2423  }
2424 
2425  _md_fd = 0;
2426  }
2427 
2429  {
2430  // Select video node streaming format
2432 
2433  // Configure metadata node stream format
2434  v4l2_format fmt{ };
2435  fmt.type = _md_type;
2436 
2437  if (xioctl(_md_fd, VIDIOC_G_FMT, &fmt))
2438  {
2439  return; // Does not throw, MIPI device metadata not received through UVC, no metadata here may be valid
2440  }
2441 
2442  if (fmt.type != _md_type)
2443  throw linux_backend_exception("ioctl(VIDIOC_G_FMT): " + _md_name + " node is not metadata capture");
2444 
2445  bool success = false;
2446 
2447  for (const uint32_t& request : { V4L2_META_FMT_D4XX, V4L2_META_FMT_UVC})
2448  {
2449  // Configure metadata format - try d4xx, then fallback to currently retrieve UVC default header of 12 bytes
2450  memcpy(fmt.fmt.raw_data, &request, sizeof(request));
2451  // use only for IPU6?
2452  if ((_dev.cap.capabilities & V4L2_CAP_VIDEO_CAPTURE_MPLANE) && !is_platform_jetson())
2453  {
2454  /* Sakari patch for videodev2.h. This structure will be within kernel > 6.4 */
2455  struct v4l2_meta_format {
2456  uint32_t dataformat;
2457  uint32_t buffersize;
2458  uint32_t width;
2459  uint32_t height;
2460  uint32_t bytesperline;
2461  } meta;
2462  // copy fmt from g_fmt ioctl
2463  memcpy(&meta, fmt.fmt.raw_data, sizeof(meta));
2464  // set fmt width, d4xx metadata is only one line
2465  meta.dataformat = request;
2466  meta.width = profile.width;
2467  meta.height = 1;
2468  memcpy(fmt.fmt.raw_data, &meta, sizeof(meta));
2469  }
2470 
2471  if(xioctl(_md_fd, VIDIOC_S_FMT, &fmt) >= 0)
2472  {
2473  LOG_INFO("Metadata node was successfully configured to " << fourcc_to_string(request) << " format" <<", fd " << std::dec <<_md_fd);
2474  success =true;
2475  break;
2476  }
2477  else
2478  {
2479  LOG_WARNING("Metadata node configuration failed for " << fourcc_to_string(request));
2480  }
2481  }
2482 
2483  if (!success)
2484  throw linux_backend_exception(_md_name + " ioctl(VIDIOC_S_FMT) for metadata node failed");
2485 
2486  }
2487 
2489  {
2490  if (_md_fd != -1)
2491  {
2492  // D457 development - added for mipi device, for IR because no metadata there
2493  // Meta node to be initialized first to enforce initial sync
2494  for (auto&& buf : _md_buffers) buf->prepare_for_streaming(_md_fd);
2495  }
2496 
2497  // Request streaming for video node
2499  }
2500 
2501  // Retrieve metadata from a dedicated UVC node. For kernels 4.16+
2502  void v4l_uvc_meta_device::acquire_metadata(buffers_mgr & buf_mgr,fd_set &fds, bool)
2503  {
2504  //Use non-blocking metadata node polling
2505  if(_md_fd > 0 && FD_ISSET(_md_fd, &fds))
2506  {
2507  // In scenario if [md+vid] ->[md] ->[md,vid] the third md should not be retrieved but wait for next select
2508  if (buf_mgr.metadata_size())
2509  {
2510  LOG_WARNING("Metadata override requested but avoided skipped");
2511  // D457 wa - return removed
2512  //return;
2513  // In scenario: {vid[i]} ->{md[i]} ->{md[i+1],vid[i+1]}:
2514  // - vid[i] will be uploaded to user callback without metadata (for now)
2515  // - md[i] will be dropped
2516  // - vid[i+1] and md[i+1] will be uploaded together - back to stable stream
2517  auto md_buf = buf_mgr.get_buffers().at(e_metadata_buf);
2518  md_buf._data_buf->request_next_frame(md_buf._file_desc,true);
2519  }
2520  FD_CLR(_md_fd,&fds);
2521 
2522  v4l2_buffer buf{};
2523  buf.type = _md_type;
2524  buf.memory = _use_memory_map ? V4L2_MEMORY_MMAP : V4L2_MEMORY_USERPTR;
2525 
2526  // W/O multiplexing this will create a blocking call for metadata node
2527  if(xioctl(_md_fd, VIDIOC_DQBUF, &buf) < 0)
2528  {
2529  LOG_DEBUG_V4L("Dequeued empty buf for md fd " << std::dec << _md_fd);
2530  }
2531 
2532  //V4l debugging message
2533  auto mdbuf = _md_buffers[buf.index]->get_frame_start();
2534  auto hwts = *(uint32_t*)((mdbuf+2));
2535  auto fn = *(uint32_t*)((mdbuf+38));
2536  LOG_DEBUG_V4L("Dequeued md buf " << std::dec << buf.index << " for fd " << _md_fd << " seq " << buf.sequence
2537  << " fn " << fn << " hw ts " << hwts
2538  << " v4lbuf ts usec " << buf.timestamp.tv_usec);
2539 
2540  auto buffer = _md_buffers[buf.index];
2542 
2543  // pushing metadata buffer to syncer
2544  _video_md_syncer.push_metadata({std::make_shared<v4l2_buffer>(buf), _md_fd, buf.index});
2545  buf_mgr.handle_buffer(e_metadata_buf, -1);
2546  }
2547  }
2548 
2550  v4l_uvc_meta_device(info,use_memory_map)
2551  {}
2552 
2554  {}
2555 
2556  // D457 controls map- temporal solution to bypass backend interface with actual codes
2557  // DS5 depth XU identifiers
2568  const uint8_t RS_LED_PWR = 0xE;
2569  const uint8_t RS_EMITTER_FREQUENCY = 0x10; // Match to DS5_EMITTER_FREQUENCY
2570 
2571 
2573  {
2574  v4l2_ext_control control{get_cid(opt), 0, 0, 0};
2575  // Extract the control group from the underlying control query
2576  v4l2_ext_controls ctrls_block { control.id&0xffff0000, 1, 0, 0, 0, &control};
2577 
2578  if (xioctl(_fd, VIDIOC_G_EXT_CTRLS, &ctrls_block) < 0)
2579  {
2580  if (errno == EIO || errno == EAGAIN) // TODO: Log?
2581  return false;
2582 
2583  throw linux_backend_exception("xioctl(VIDIOC_G_EXT_CTRLS) failed");
2584  }
2585 
2587  control.value = (V4L2_EXPOSURE_MANUAL==control.value) ? 0 : 1;
2588  value = control.value;
2589 
2590  return true;
2591  }
2592 
2594  {
2595  v4l2_ext_control control{get_cid(opt), 0, 0, value};
2597  control.value = value ? V4L2_EXPOSURE_APERTURE_PRIORITY : V4L2_EXPOSURE_MANUAL;
2598 
2599  // Extract the control group from the underlying control query
2600  v4l2_ext_controls ctrls_block{ control.id & 0xffff0000, 1, 0, 0, 0, &control };
2601  if (xioctl(_fd, VIDIOC_S_EXT_CTRLS, &ctrls_block) < 0)
2602  {
2603  if (errno == EIO || errno == EAGAIN) // TODO: Log?
2604  return false;
2605 
2606  throw linux_backend_exception("xioctl(VIDIOC_S_EXT_CTRLS) failed");
2607  }
2608 
2609  return true;
2610  }
2611 
2613  {
2614  v4l2_ext_control xctrl{xu_to_cid(xu,control), uint32_t(size), 0, 0};
2615  switch (size)
2616  {
2617  case 1: xctrl.value = *(reinterpret_cast<const uint8_t*>(data)); break;
2618  case 2: xctrl.value = *reinterpret_cast<const uint16_t*>(data); break; // TODO check signed/unsigned
2619  case 4: xctrl.value = *reinterpret_cast<const int32_t*>(data); break;
2620  case 8: xctrl.value64 = *reinterpret_cast<const int64_t*>(data); break;
2621  default:
2622  xctrl.p_u8 = const_cast<uint8_t*>(data); // TODO aggregate initialization with union
2623  }
2624 
2626  xctrl.value = xctrl.value ? V4L2_EXPOSURE_APERTURE_PRIORITY : V4L2_EXPOSURE_MANUAL;
2627 
2628  // Extract the control group from the underlying control query
2629  v4l2_ext_controls ctrls_block { xctrl.id&0xffff0000, 1, 0, 0, 0, &xctrl };
2630 
2631  int retVal = xioctl(_fd, VIDIOC_S_EXT_CTRLS, &ctrls_block);
2632  if (retVal < 0)
2633  {
2634  if (errno == EIO || errno == EAGAIN) // TODO: Log?
2635  return false;
2636 
2637  throw linux_backend_exception("xioctl(VIDIOC_S_EXT_CTRLS) failed");
2638  }
2639  return true;
2640  }
2641 
2643  {
2644  v4l2_ext_control xctrl{xu_to_cid(xu,control), uint32_t(size), 0, 0};
2645  xctrl.p_u8 = data;
2646 
2647  v4l2_ext_controls ext {xctrl.id & 0xffff0000, 1, 0, 0, 0, &xctrl};
2648 
2649  // the ioctl fails once when performing send and receive right after it
2650  // it succeeds on the second time
2651  int tries = 2;
2652  while(tries--)
2653  {
2654  int ret = xioctl(_fd, VIDIOC_G_EXT_CTRLS, &ext);
2655  if (ret < 0)
2656  {
2657  // exception is thrown if the ioctl fails twice
2658  continue;
2659  }
2660 
2662  xctrl.value = (V4L2_EXPOSURE_MANUAL == xctrl.value) ? 0 : 1;
2663 
2664  // used to parse the data when only a value is returned (e.g. laser power),
2665  // and not a pointer to a buffer of data (e.g. gvd)
2666  if (size < sizeof(__s64))
2667  memcpy(data,(void*)(&xctrl.value), size);
2668 
2669  return true;
2670  }
2671 
2672  // sending error on ioctl failure
2673  if (errno == EIO || errno == EAGAIN) // TODO: Log?
2674  return false;
2675  throw linux_backend_exception("xioctl(VIDIOC_G_EXT_CTRLS) failed");
2676  }
2677 
2679  {
2680  v4l2_query_ext_ctrl xctrl_query{};
2681  xctrl_query.id = xu_to_cid(xu,control);
2682 
2683  if(0 > ioctl(_fd,VIDIOC_QUERY_EXT_CTRL,&xctrl_query)){
2684  throw linux_backend_exception(rsutils::string::from() << "xioctl(VIDIOC_QUERY_EXT_CTRL) failed, errno=" << errno);
2685  }
2686 
2687  if ((xctrl_query.elems !=1 ) ||
2688  (xctrl_query.minimum < std::numeric_limits<int32_t>::min()) ||
2689  (xctrl_query.maximum > std::numeric_limits<int32_t>::max()))
2690  throw linux_backend_exception(rsutils::string::from() << "Mipi Control range for " << xctrl_query.name
2691  << " is not compliant with backend interface: [min,max,default,step]:\n"
2692  << xctrl_query.minimum << ", " << xctrl_query.maximum << ", "
2693  << xctrl_query.default_value << ", " << xctrl_query.step
2694  << "\n Elements = " << xctrl_query.elems);
2695 
2697  return {0, 1, 1, 1};
2698  return { static_cast<int32_t>(xctrl_query.minimum), static_cast<int32_t>(xctrl_query.maximum),
2699  static_cast<int32_t>(xctrl_query.step), static_cast<int32_t>(xctrl_query.default_value)};
2700  }
2701 
2703  {
2705  }
2706 
2708  {
2709  switch(option)
2710  {
2711  case RS2_OPTION_BACKLIGHT_COMPENSATION: return V4L2_CID_BACKLIGHT_COMPENSATION;
2712  case RS2_OPTION_BRIGHTNESS: return V4L2_CID_BRIGHTNESS;
2713  case RS2_OPTION_CONTRAST: return V4L2_CID_CONTRAST;
2714  case RS2_OPTION_EXPOSURE: return V4L2_CID_EXPOSURE_ABSOLUTE; // Is this actually valid? I'm getting a lot of VIDIOC error 22s...
2715  case RS2_OPTION_GAIN: return V4L2_CTRL_CLASS_IMAGE_SOURCE | 0x903; // v4l2-ctl --list-ctrls -d /dev/video0
2716  case RS2_OPTION_GAMMA: return V4L2_CID_GAMMA;
2717  case RS2_OPTION_HUE: return V4L2_CID_HUE;
2718  case RS2_OPTION_LASER_POWER: return V4L2_CID_EXPOSURE_ABSOLUTE;
2719  case RS2_OPTION_EMITTER_ENABLED: return V4L2_CID_EXPOSURE_AUTO;
2720 // case RS2_OPTION_SATURATION: return V4L2_CID_SATURATION;
2721 // case RS2_OPTION_SHARPNESS: return V4L2_CID_SHARPNESS;
2722 // case RS2_OPTION_WHITE_BALANCE: return V4L2_CID_WHITE_BALANCE_TEMPERATURE;
2723  case RS2_OPTION_ENABLE_AUTO_EXPOSURE: return V4L2_CID_EXPOSURE_AUTO; // Automatic gain/exposure control
2724 // case RS2_OPTION_ENABLE_AUTO_WHITE_BALANCE: return V4L2_CID_AUTO_WHITE_BALANCE;
2725 // case RS2_OPTION_POWER_LINE_FREQUENCY : return V4L2_CID_POWER_LINE_FREQUENCY;
2726 // case RS2_OPTION_AUTO_EXPOSURE_PRIORITY: return V4L2_CID_EXPOSURE_AUTO_PRIORITY;
2727  default: throw linux_backend_exception(rsutils::string::from() << "no v4l2 mipi mapping cid for option " << option);
2728  }
2729  }
2730 
2731  // D457 controls map - temporal solution to bypass backend interface with actual codes
2733  {
2734  if (0==xu.subdevice)
2735  {
2736  switch(control)
2737  {
2738  case RS_HWMONITOR: return RS_CAMERA_CID_HWMC;
2740  case RS_EXPOSURE: return V4L2_CID_EXPOSURE_ABSOLUTE;//RS_CAMERA_CID_MANUAL_EXPOSURE; V4L2_CID_EXPOSURE_ABSOLUTE
2743  case RS_ENABLE_AUTO_EXPOSURE: return V4L2_CID_EXPOSURE_AUTO; //RS_CAMERA_CID_EXPOSURE_MODE;
2746  // D457 Missing functionality
2747  //case RS_ERROR_REPORTING: TBD;
2748  //case RS_EXT_TRIGGER: TBD;
2749  //case RS_ASIC_AND_PROJECTOR_TEMPERATURES: TBD;
2750  //case RS_LED_PWR: TBD;
2751 
2752  default: throw linux_backend_exception(rsutils::string::from() << "no v4l2 mipi cid for XU depth control " << std::dec << int(control));
2753  }
2754  }
2755  else
2756  throw linux_backend_exception(rsutils::string::from() << "MIPI Controls mapping is for Depth XU only, requested for subdevice " << xu.subdevice);
2757  }
2758 
2759  std::shared_ptr<uvc_device> v4l_backend::create_uvc_device(uvc_device_info info) const
2760  {
2761  bool mipi_device = 0xABCD == info.pid; // D457 development. Not for upstream
2762  auto v4l_uvc_dev = mipi_device ? std::make_shared<v4l_mipi_device>(info) :
2763  ((!info.has_metadata_node) ? std::make_shared<v4l_uvc_device>(info) :
2764  std::make_shared<v4l_uvc_meta_device>(info));
2765 
2766  return std::make_shared<platform::retry_controls_work_around>(v4l_uvc_dev);
2767  }
2768 
2769  std::vector<uvc_device_info> v4l_backend::query_uvc_devices() const
2770  {
2771  std::vector<uvc_device_info> uvc_nodes;
2773  [&uvc_nodes](const uvc_device_info& i, const std::string&)
2774  {
2775  uvc_nodes.push_back(i);
2776  });
2777 
2778  return uvc_nodes;
2779  }
2780 
2781  std::shared_ptr<command_transfer> v4l_backend::create_usb_device(usb_device_info info) const
2782  {
2784  if(dev)
2785  return std::make_shared<platform::command_transfer_usb>(dev);
2786  return nullptr;
2787  }
2788 
2789  std::vector<usb_device_info> v4l_backend::query_usb_devices() const
2790  {
2791  auto device_infos = usb_enumerator::query_devices_info();
2792  return device_infos;
2793  }
2794 
2795  std::shared_ptr<hid_device> v4l_backend::create_hid_device(hid_device_info info) const
2796  {
2797  return std::make_shared<v4l_hid_device>(info);
2798  }
2799 
2800  std::vector<hid_device_info> v4l_backend::query_hid_devices() const
2801  {
2802  std::vector<hid_device_info> results;
2803  v4l_hid_device::foreach_hid_device([&](const hid_device_info& hid_dev_info){
2804  results.push_back(hid_dev_info);
2805  });
2806  return results;
2807  }
2808 
2809  std::shared_ptr<device_watcher> v4l_backend::create_device_watcher() const
2810  {
2811 #if defined(USING_UDEV)
2812  return std::make_shared< udev_device_watcher >( this );
2813 #else
2814  return std::make_shared< polling_device_watcher >( this );
2815 #endif
2816  }
2817 
2818  std::shared_ptr<backend> create_backend()
2819  {
2820  return std::make_shared<v4l_backend>();
2821  }
2822 
2824  {
2825  std::lock_guard<std::mutex> lock(_syncer_mutex);
2826  if(!_is_ready)
2827  {
2828  LOG_DEBUG_V4L("video_md_syncer - push_video called but syncer not ready");
2829  return;
2830  }
2831  _video_queue.push(video_buffer);
2832  LOG_DEBUG_V4L("video_md_syncer - video pushed with sequence " << video_buffer._v4l2_buf->sequence << ", buf " << video_buffer._buffer_index);
2833 
2834  // remove old video_buffer
2835  if (_video_queue.size() > 2)
2836  {
2837  // Enqueue of video buffer before throwing its content away
2839  }
2840  }
2841 
2843  {
2844  std::lock_guard<std::mutex> lock(_syncer_mutex);
2845  if(!_is_ready)
2846  {
2847  LOG_DEBUG_V4L("video_md_syncer - push_metadata called but syncer not ready");
2848  return;
2849  }
2850  // override front buffer if it has the same sequence that the new buffer - happens with metadata sequence 0
2851  if (_md_queue.size() > 0 && _md_queue.front()._v4l2_buf->sequence == md_buffer._v4l2_buf->sequence)
2852  {
2853  LOG_DEBUG_V4L("video_md_syncer - calling enqueue_front_buffer_before_throwing_it - md buf " << md_buffer._buffer_index << " and md buf " << _md_queue.front()._buffer_index << " have same sequence");
2855  }
2856  _md_queue.push(md_buffer);
2857  LOG_DEBUG_V4L("video_md_syncer - md pushed with sequence " << md_buffer._v4l2_buf->sequence << ", buf " << md_buffer._buffer_index);
2858  LOG_DEBUG_V4L("video_md_syncer - md queue size = " << _md_queue.size());
2859 
2860  // remove old md_buffer
2861  if (_md_queue.size() > 2)
2862  {
2863  LOG_DEBUG_V4L("video_md_syncer - calling enqueue_front_buffer_before_throwing_it - md queue size is: " << _md_queue.size());
2864  // Enqueue of md buffer before throwing its content away
2866  }
2867  }
2868 
2869  bool v4l2_video_md_syncer::pull_video_with_metadata(std::shared_ptr<v4l2_buffer>& video_buffer, std::shared_ptr<v4l2_buffer>& md_buffer,
2870  int& video_fd, int& md_fd)
2871  {
2872  std::lock_guard<std::mutex> lock(_syncer_mutex);
2873  if(!_is_ready)
2874  {
2875  LOG_DEBUG_V4L("video_md_syncer - pull_video_with_metadata called but syncer not ready");
2876  return false;
2877  }
2878  if (_video_queue.empty())
2879  {
2880  LOG_DEBUG_V4L("video_md_syncer - video queue is empty");
2881  return false;
2882  }
2883 
2884  if (_md_queue.empty())
2885  {
2886  LOG_DEBUG_V4L("video_md_syncer - md queue is empty");
2887  return false;
2888  }
2889 
2890  sync_buffer video_candidate = _video_queue.front();
2891  sync_buffer md_candidate = _md_queue.front();
2892 
2893  // set video and md file descriptors
2894  video_fd = video_candidate._fd;
2895  md_fd = md_candidate._fd;
2896 
2897  // sync is ok if latest video and md have the same sequence
2898  if (video_candidate._v4l2_buf->sequence == md_candidate._v4l2_buf->sequence)
2899  {
2900  video_buffer = video_candidate._v4l2_buf;
2901  md_buffer = md_candidate._v4l2_buf;
2902  // removing from queues
2903  _video_queue.pop();
2904  _md_queue.pop();
2905  LOG_DEBUG_V4L("video_md_syncer - video and md pulled with sequence " << video_candidate._v4l2_buf->sequence);
2906  return true;
2907  }
2908 
2909  LOG_DEBUG_V4L("video_md_syncer - video_candidate seq " << video_candidate._v4l2_buf->sequence << ", md_candidate seq " << md_candidate._v4l2_buf->sequence);
2910 
2911  if (video_candidate._v4l2_buf->sequence > md_candidate._v4l2_buf->sequence && _md_queue.size() > 1)
2912  {
2913  // Enqueue of md buffer before throwing its content away
2914  enqueue_buffer_before_throwing_it(md_candidate);
2915  _md_queue.pop();
2916 
2917  // checking remaining metadata buffer in queue
2918  auto alternative_md_candidate = _md_queue.front();
2919  // sync is ok if latest video and md have the same sequence
2920  if (video_candidate._v4l2_buf->sequence == alternative_md_candidate._v4l2_buf->sequence)
2921  {
2922  video_buffer = video_candidate._v4l2_buf;
2923  md_buffer = alternative_md_candidate._v4l2_buf;
2924  // removing from queues
2925  _video_queue.pop();
2926  _md_queue.pop();
2927  LOG_DEBUG_V4L("video_md_syncer - video and md pulled with sequence " << video_candidate._v4l2_buf->sequence);
2928  return true;
2929  }
2930  }
2931  if (video_candidate._v4l2_buf->sequence < md_candidate._v4l2_buf->sequence && _video_queue.size() > 1)
2932  {
2933  // Enqueue of md buffer before throwing its content away
2934  enqueue_buffer_before_throwing_it(video_candidate);
2935  _video_queue.pop();
2936 
2937  // checking remaining video buffer in queue
2938  auto alternative_video_candidate = _video_queue.front();
2939  // sync is ok if latest video and md have the same sequence
2940  if (alternative_video_candidate._v4l2_buf->sequence == md_candidate._v4l2_buf->sequence)
2941  {
2942  video_buffer = alternative_video_candidate._v4l2_buf;
2943  md_buffer = md_candidate._v4l2_buf;
2944  // removing from queues
2945  _video_queue.pop();
2946  _md_queue.pop();
2947  LOG_DEBUG_V4L("video_md_syncer - video and md pulled with sequence " << md_candidate._v4l2_buf->sequence);
2948  return true;
2949  }
2950  }
2951  return false;
2952  }
2953 
2955  {
2956  // Enqueue of buffer before throwing its content away
2957  LOG_DEBUG_V4L("video_md_syncer - Enqueue buf " << std::dec << sb._buffer_index << " for fd " << sb._fd << " before dropping it");
2958  if (xioctl(sb._fd, VIDIOC_QBUF, sb._v4l2_buf.get()) < 0)
2959  {
2960  LOG_ERROR("xioctl(VIDIOC_QBUF) failed when requesting new frame! fd: " << sb._fd << " error: " << strerror(errno));
2961  }
2962  }
2963 
2964  void v4l2_video_md_syncer::enqueue_front_buffer_before_throwing_it(std::queue<sync_buffer>& sync_queue)
2965  {
2966  // Enqueue of buffer before throwing its content away
2967  LOG_DEBUG_V4L("video_md_syncer - Enqueue buf " << std::dec << sync_queue.front()._buffer_index << " for fd " << sync_queue.front()._fd << " before dropping it");
2968  if (xioctl(sync_queue.front()._fd, VIDIOC_QBUF, sync_queue.front()._v4l2_buf.get()) < 0)
2969  {
2970  LOG_ERROR("xioctl(VIDIOC_QBUF) failed when requesting new frame! fd: " << sync_queue.front()._fd << " error: " << strerror(errno));
2971  }
2972  sync_queue.pop();
2973  }
2974 
2975 
2977  {
2978  _is_ready = false;
2979  flush_queues();
2980  }
2981 
2983  {
2984  // Empty queues
2985  LOG_DEBUG_V4L("video_md_syncer - flush video and md queues");
2986  std::lock_guard<std::mutex> lock(_syncer_mutex);
2987  while(!_video_queue.empty())
2988  {
2989  _video_queue.pop();
2990  }
2991  while(!_md_queue.empty())
2992  {
2993  _md_queue.pop();
2994  }
2995  LOG_DEBUG_V4L("video_md_syncer - flush video and md queues done - mq_q size = " << _md_queue.size() << ", video_q size = " << _video_queue.size());
2996  }
2997  }
2998 }
librealsense::platform::v4l2_video_md_syncer::enqueue_buffer_before_throwing_it
void enqueue_buffer_before_throwing_it(const sync_buffer &sb) const
Definition: backend-v4l2.cpp:2954
librealsense::platform::v4l_mipi_device::set_xu
bool set_xu(const extension_unit &xu, uint8_t control, const uint8_t *data, int size) override
Definition: backend-v4l2.cpp:2612
librealsense::platform::v4l_uvc_meta_device::negotiate_kernel_buffers
void negotiate_kernel_buffers(size_t num) const
Definition: backend-v4l2.cpp:2338
librealsense::platform::v4l_uvc_device::get_pu
bool get_pu(rs2_option opt, int32_t &value) const override
Definition: backend-v4l2.cpp:1878
librealsense::platform::buffers_mgr::metadata_size
uint8_t metadata_size() const
Definition: backend-v4l2.h:217
length
GLenum GLuint GLenum GLsizei length
Definition: glad/glad/glad.h:135
RS_CAMERA_CID_AE_SETPOINT_SET
constexpr uint32_t RS_CAMERA_CID_AE_SETPOINT_SET
Definition: backend-v4l2.cpp:80
librealsense::platform::v4l_uvc_device::unsubscribe_from_ctrl_event
void unsubscribe_from_ctrl_event(uint32_t control_id)
Definition: backend-v4l2.cpp:2258
unit-test-config.dir
dir
Definition: unit-test-config.py:81
UVC_GET_CUR
@ UVC_GET_CUR
Definition: uvc-types.h:128
librealsense
Definition: algo.h:18
librealsense::platform::named_mutex::close
void close()
Definition: win-helpers.cpp:952
librealsense::md_header::md_type_id
md_type md_type_id
Definition: src/metadata.h:288
test-fw-update.cmd
list cmd
Definition: test-fw-update.py:141
librealsense::platform::uvc_device_info::has_metadata_node
bool has_metadata_node
Definition: uvc-device-info.h:27
count
GLint GLsizei count
Definition: glad/glad/glad.h:2301
uint8_t
unsigned char uint8_t
Definition: stdint.h:78
test-record-software-device.vs
def vs
Definition: test-record-software-device.py:155
realdds::topics::metadata::header::key::timestamp
const std::string timestamp
Definition: dds/test-metadata.py:173
librealsense::platform::e_max_kernel_buf_type
@ e_max_kernel_buf_type
Definition: backend-v4l2.h:161
librealsense::platform::v4l_uvc_device::get_pu_range
control_range get_pu_range(rs2_option option) const override
Definition: backend-v4l2.cpp:1934
librealsense::platform::v4l_uvc_device
Definition: backend-v4l2.h:313
min
int min(int a, int b)
Definition: lz4s.c:73
librealsense::platform::v4l2_video_md_syncer::_md_queue
std::queue< sync_buffer > _md_queue
Definition: backend-v4l2.h:289
librealsense::platform::v4l_uvc_device::_name
std::string _name
Definition: backend-v4l2.h:408
librealsense::md_type::META_DATA_HID_IMU_REPORT_ID
@ META_DATA_HID_IMU_REPORT_ID
test-librs-connections.n
n
Definition: test-librs-connections.py:38
librealsense::platform::v4l_uvc_device::stop_data_capture
virtual void stop_data_capture() override
Definition: backend-v4l2.cpp:1282
librealsense::hid_header::report_type
uint8_t report_type
Definition: src/metadata.h:798
librealsense::platform::v4l_uvc_device::set_format
virtual void set_format(stream_profile profile) override
Definition: backend-v4l2.cpp:2213
librealsense::platform::buffer::_type
v4l2_buf_type _type
Definition: backend-v4l2.h:145
id
GLenum GLuint id
Definition: glad/glad/glad.h:135
librealsense::platform::v4l_mipi_device::is_platform_jetson
bool is_platform_jetson() const override
Definition: backend-v4l2.cpp:1741
RS_CAMERA_CID_EXPOSURE_MODE
constexpr uint32_t RS_CAMERA_CID_EXPOSURE_MODE
Definition: backend-v4l2.cpp:89
std::to_string
std::string to_string(T value)
Definition: android_helpers.h:16
RS_CAMERA_CID_HWMC
constexpr uint32_t RS_CAMERA_CID_HWMC
Definition: backend-v4l2.cpp:93
librealsense::platform::buffer::_buf
v4l2_buffer _buf
Definition: backend-v4l2.h:152
librealsense::platform::v4l_uvc_device::stop_callbacks
void stop_callbacks() override
Definition: backend-v4l2.cpp:1302
librealsense::platform::buffer::_mutex
std::mutex _mutex
Definition: backend-v4l2.h:153
rspy.file.find
def find(dir, mask)
Definition: file.py:45
librealsense::platform::hid_device_info
Definition: hid-device-info.h:13
librealsense::platform::v4l_uvc_device::get_xu
bool get_xu(const extension_unit &xu, uint8_t control, uint8_t *data, int size) const override
Definition: backend-v4l2.cpp:1787
librealsense::platform::v4l_uvc_device::subscribe_to_ctrl_event
void subscribe_to_ctrl_event(uint32_t control_id)
Definition: backend-v4l2.cpp:2245
RS_CAMERA_CID_MANUAL_EXPOSURE
constexpr uint32_t RS_CAMERA_CID_MANUAL_EXPOSURE
Definition: backend-v4l2.cpp:87
RS2_OPTION_ENABLE_AUTO_EXPOSURE
@ RS2_OPTION_ENABLE_AUTO_EXPOSURE
Definition: rs_option.h:38
librealsense::ds::success
@ success
Definition: d400-private.h:266
librealsense::platform::v4l2_video_md_syncer::stop
void stop()
Definition: backend-v4l2.cpp:2976
librealsense::platform::named_mutex::_mutex
std::mutex _mutex
Definition: backend-v4l2.h:118
test-y16-calibration-format.timer
timer
Definition: test-y16-calibration-format.py:31
RS2_OPTION_CONTRAST
@ RS2_OPTION_CONTRAST
Definition: rs_option.h:30
librealsense::platform::v4l_uvc_device::fourcc_to_string
std::string fourcc_to_string(uint32_t id) const
Definition: backend-v4l2.cpp:1326
librealsense::hid_mipi_data
Definition: hid-data.h:20
librealsense::platform::v4l_mipi_device::get_cid
virtual uint32_t get_cid(rs2_option option) const
Definition: backend-v4l2.cpp:2707
librealsense::platform::v4l_uvc_meta_device::v4l_uvc_meta_device
v4l_uvc_meta_device(const uvc_device_info &info, bool use_memory_map=false)
Definition: backend-v4l2.cpp:2290
time-service.h
uint16_t
unsigned short uint16_t
Definition: stdint.h:79
for
for(int i=0 ;i< 32;++i)
Definition: test-dispatcher.cpp:68
rspy.devices.path
path
Definition: unit-tests/py/rspy/devices.py:47
librealsense::platform::named_mutex::_object_lock_counter
int _object_lock_counter
Definition: backend-v4l2.h:117
profile::format
rs2_format format
Definition: unit-tests-common.h:61
librealsense::platform::frame_drop_monitor::update_and_check_kpi
bool update_and_check_kpi(const stream_profile &profile, const timeval &timestamp)
Definition: backend-v4l2.cpp:1090
librealsense::platform::v4l_uvc_device::populate_imu_data
void populate_imu_data(metadata_hid_raw &meta_data, uint8_t *frame_start, uint8_t &md_size, void **md_start) const
Definition: backend-v4l2.cpp:1657
librealsense::platform::buffers_mgr::_md_size
uint8_t _md_size
Definition: backend-v4l2.h:231
librealsense::platform::size
@ size
Definition: platform/hid-device.h:64
librealsense::md_imu_report::header
md_header header
Definition: src/metadata.h:763
librealsense::platform::v4l_mipi_device::~v4l_mipi_device
virtual ~v4l_mipi_device()
Definition: backend-v4l2.cpp:2553
librealsense::platform::time_in_HH_MM_SS_MMM
std::string time_in_HH_MM_SS_MMM()
Definition: backend-v4l2.cpp:1345
RS_CAMERA_CID_AE_ROI_GET
constexpr uint32_t RS_CAMERA_CID_AE_ROI_GET
Definition: backend-v4l2.cpp:77
V4L2_CAP_META_CAPTURE
#define V4L2_CAP_META_CAPTURE
Definition: backend-v4l2.h:57
librealsense::platform::v4l_uvc_device::poll
void poll()
Definition: backend-v4l2.cpp:1369
librealsense::platform::v4l_uvc_meta_device::prepare_capture_buffers
void prepare_capture_buffers()
Definition: backend-v4l2.cpp:2488
librealsense::md_hid_report::imu_report
md_imu_report imu_report
Definition: src/metadata.h:790
librealsense::platform::v4l_uvc_device::close
void close(stream_profile) override
Definition: backend-v4l2.cpp:1307
RS2_LOG_SEVERITY_WARN
@ RS2_LOG_SEVERITY_WARN
Definition: rs_types.h:124
librealsense::platform::v4l_uvc_meta_device::_md_type
v4l2_buf_type _md_type
Definition: backend-v4l2.h:466
index
GLuint index
Definition: glad/glad/glad.h:2777
RS2_OPTION_BACKLIGHT_COMPENSATION
@ RS2_OPTION_BACKLIGHT_COMPENSATION
Definition: rs_option.h:28
librealsense::platform::v4l_uvc_device::capture_loop
virtual void capture_loop() override
Definition: backend-v4l2.cpp:2079
librealsense::platform::v4l_uvc_device::_buf_dispatch
buffers_mgr _buf_dispatch
Definition: backend-v4l2.h:430
librealsense::metadata_hid_raw
metadata_hid_raw - HID metadata structure layout populated by backend
Definition: src/metadata.h:807
string
GLsizei const GLchar *const * string
Definition: glad/glad/glad.h:2861
librealsense::platform::buffer::_offset
uint32_t _offset
Definition: backend-v4l2.h:149
q
GLdouble GLdouble GLdouble q
Definition: glad/glad/glad.h:1877
librealsense::platform::named_mutex::_init_mutex
static std::recursive_mutex _init_mutex
Definition: backend-v4l2.h:114
librealsense::platform::named_mutex::lock
void lock()
Definition: backend-v4l2.cpp:191
librealsense::platform::named_mutex::unlock
void unlock()
Definition: backend-v4l2.cpp:197
librealsense::platform::v4l2_video_md_syncer::start
void start()
Definition: backend-v4l2.h:279
librealsense::platform::RS_DEPTH_EMITTER_ENABLED
const uint8_t RS_DEPTH_EMITTER_ENABLED
Definition: backend-v4l2.cpp:2559
librealsense::platform::v4l_uvc_device::allocate_io_buffers
virtual void allocate_io_buffers(size_t num) override
Definition: backend-v4l2.cpp:2120
librealsense::platform::v4l2_video_md_syncer::push_video
void push_video(const sync_buffer &video_buffer)
Definition: backend-v4l2.cpp:2823
RS_CAMERA_CID_ERB
constexpr uint32_t RS_CAMERA_CID_ERB
Definition: backend-v4l2.cpp:81
profile::fps
int fps
Definition: unit-tests-common.h:65
void
typedef void(APIENTRY *GLDEBUGPROC)(GLenum source
librealsense::md_header::md_size
uint32_t md_size
Definition: src/metadata.h:289
librealsense::platform::v4l_uvc_device::_buffers
std::vector< std::shared_ptr< buffer > > _buffers
Definition: backend-v4l2.h:413
LOG_DEBUG
#define LOG_DEBUG(...)
Definition: easyloggingpp.h:70
RS_CAMERA_CID_FW_VERSION
constexpr uint32_t RS_CAMERA_CID_FW_VERSION
Definition: backend-v4l2.cpp:75
librealsense::platform::v4l_uvc_device::get_md_buffer
virtual std::shared_ptr< buffer > get_md_buffer(__u32 index) const
Definition: backend-v4l2.h:405
LOCAL_V4L2_BUF_TYPE_META_CAPTURE
constexpr auto LOCAL_V4L2_BUF_TYPE_META_CAPTURE
Definition: backend-v4l2.h:74
librealsense::platform::v4l_uvc_meta_device::_md_name
std::string _md_name
Definition: backend-v4l2.h:465
example1 - object detection.num
num
Definition: example1 - object detection.py:54
librealsense::platform::get_usb_connection_type
static usb_spec get_usb_connection_type(std::string path)
Definition: backend-v4l2.cpp:504
librealsense::platform::v4l_uvc_device::set_metadata_attributes
virtual void set_metadata_attributes(buffers_mgr &buf_mgr, __u32 bytesused, uint8_t *md_start)
Definition: backend-v4l2.cpp:1729
librealsense::platform::v4l_uvc_device::negotiate_kernel_buffers
virtual void negotiate_kernel_buffers(size_t num) const override
Definition: backend-v4l2.cpp:2113
librealsense::hid_header::timestamp
uint64_t timestamp
Definition: src/metadata.h:799
from.h
librealsense::platform::v4l2_video_md_syncer::sync_buffer::_buffer_index
__u32 _buffer_index
Definition: backend-v4l2.h:266
run-unit-tests.regex
regex
Definition: run-unit-tests.py:85
librealsense::platform::RS_EXPOSURE
const uint8_t RS_EXPOSURE
Definition: backend-v4l2.cpp:2560
MAX_META_DATA_SIZE
const uint8_t MAX_META_DATA_SIZE
Definition: backend.h:20
librealsense::platform::named_mutex::~named_mutex
~named_mutex()
Definition: backend-v4l2.cpp:179
current_time
long long current_time()
Definition: unit-tests-internal.cpp:29
librealsense::hid_report_imu
@ hid_report_imu
Definition: src/metadata.h:250
librealsense::platform::buffers_mgr::verify_vd_md_sync
bool verify_vd_md_sync() const
Definition: backend-v4l2.cpp:483
librealsense::platform::usb_spec
usb_spec
Definition: usb-types.h:112
RS_CAMERA_CID_LASER_POWER_LEVEL
constexpr uint32_t RS_CAMERA_CID_LASER_POWER_LEVEL
Definition: backend-v4l2.cpp:88
librealsense::wrong_api_call_sequence_exception
Definition: librealsense-exception.h:124
profile::width
int width
Definition: unit-tests-common.h:62
librealsense::platform::v4l_uvc_device::pend_for_ctrl_status_event
bool pend_for_ctrl_status_event()
Definition: backend-v4l2.cpp:2272
RS2_OPTION_WHITE_BALANCE
@ RS2_OPTION_WHITE_BALANCE
Definition: rs_option.h:37
librealsense::platform::named_mutex::release
void release()
Definition: backend-v4l2.cpp:246
librealsense::platform::v4l_mipi_device::v4l_mipi_device
v4l_mipi_device(const uvc_device_info &info, bool use_memory_map=true)
Definition: backend-v4l2.cpp:2549
librealsense::platform::xioctl
static int xioctl(int fh, unsigned long request, void *arg)
Definition: backend-v4l2.cpp:283
librealsense::platform::RS_ENABLE_AUTO_EXPOSURE
const uint8_t RS_ENABLE_AUTO_EXPOSURE
Definition: backend-v4l2.cpp:2567
librealsense::platform::v4l_uvc_meta_device
Definition: backend-v4l2.h:441
librealsense::platform::v4l_uvc_meta_device::_md_buffers
std::vector< std::shared_ptr< buffer > > _md_buffers
Definition: backend-v4l2.h:468
librealsense::platform::v4l_uvc_meta_device::set_format
void set_format(stream_profile profile)
Definition: backend-v4l2.cpp:2428
librealsense::platform::v4l_mipi_device::get_xu_range
control_range get_xu_range(const extension_unit &xu, uint8_t control, int len) const override
Definition: backend-v4l2.cpp:2678
librealsense::platform::buffer::~buffer
~buffer()
Definition: backend-v4l2.cpp:358
librealsense::platform::buffers_mgr::handle_buffer
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)
Definition: backend-v4l2.cpp:406
librealsense::platform::buffer::get_frame_start
uint8_t * get_frame_start() const
Definition: backend-v4l2.h:140
librealsense::platform::supported_kernel_buf_types
supported_kernel_buf_types
Definition: backend-v4l2.h:157
LOG_WARNING
#define LOG_WARNING(...)
Definition: easyloggingpp.h:72
udev-device-watcher.h
librealsense::platform::v4l2_video_md_syncer::sync_buffer::_v4l2_buf
std::shared_ptr< v4l2_buffer > _v4l2_buf
Definition: backend-v4l2.h:264
librealsense::platform::v4l_uvc_device::_fds
std::vector< int > _fds
Definition: backend-v4l2.h:429
RS_CAMERA_DEPTH_CALIBRATION_TABLE_SET
constexpr uint32_t RS_CAMERA_DEPTH_CALIBRATION_TABLE_SET
Definition: backend-v4l2.cpp:72
type
GLenum type
Definition: glad/glad/glad.h:135
width
GLint GLsizei width
Definition: glad/glad/glad.h:1397
uvc_meta_buffer::sof
__u16 sof
Definition: backend-v4l2.h:80
size
GLsizeiptr size
Definition: glad/glad/glad.h:2734
librealsense::platform::v4l_uvc_device::_video_md_syncer
v4l2_video_md_syncer _video_md_syncer
Definition: backend-v4l2.h:433
RS_CAMERA_CID_HWMC_LEGACY
constexpr uint32_t RS_CAMERA_CID_HWMC_LEGACY
Definition: backend-v4l2.cpp:83
librealsense::platform::extension_unit::subdevice
int subdevice
Definition: platform/uvc-device.h:48
test-d405-calibration-stream.pid
pid
Definition: test-d405-calibration-stream.py:12
RS_CAMERA_CID_LASER_POWER
constexpr uint32_t RS_CAMERA_CID_LASER_POWER
Definition: backend-v4l2.cpp:69
RS_CAMERA_CID_AE_SETPOINT_GET
constexpr uint32_t RS_CAMERA_CID_AE_SETPOINT_GET
Definition: backend-v4l2.cpp:79
istringstream
std::istringstream istringstream
Definition: Arg.h:43
test-unit-transform.fmt
fmt
Definition: test-unit-transform.py:42
librealsense::platform::RS_ENABLE_AUTO_WHITE_BALANCE
const uint8_t RS_ENABLE_AUTO_WHITE_BALANCE
Definition: backend-v4l2.cpp:2566
librealsense::platform::v4l_uvc_device::_info
uvc_device_info _info
Definition: backend-v4l2.h:411
profile::height
int height
Definition: unit-tests-common.h:63
librealsense::platform::v4l_uvc_meta_device::unmap_device_descriptor
void unmap_device_descriptor()
Definition: backend-v4l2.cpp:2416
val
GLuint GLfloat * val
Definition: glad/glad/glad.h:3411
librealsense::metadata_hid_raw::header
hid_header header
Definition: src/metadata.h:809
librealsense::platform::v4l_uvc_device::_fd
int _fd
Definition: backend-v4l2.h:431
usb-device.h
librealsense::platform::v4l_backend::query_uvc_devices
std::vector< uvc_device_info > query_uvc_devices() const override
Definition: backend-v4l2.cpp:2769
RS2_OPTION_GAIN
@ RS2_OPTION_GAIN
Definition: rs_option.h:32
query
GLenum query
Definition: glad/glad/glad.h:2204
r
GLdouble GLdouble r
Definition: glad/glad/glad.h:1853
RS_CAMERA_CID_MANUAL_LASER_POWER
constexpr uint32_t RS_CAMERA_CID_MANUAL_LASER_POWER
Definition: backend-v4l2.cpp:70
notification.h
command-transfer.h
librealsense::platform::v4l_uvc_device::probe_and_commit
void probe_and_commit(stream_profile profile, frame_callback callback, int buffers) override
Definition: backend-v4l2.cpp:1180
data
GLboolean * data
Definition: glad/glad/glad.h:1481
librealsense::platform::v4l_uvc_device::_thread
std::unique_ptr< std::thread > _thread
Definition: backend-v4l2.h:419
UVC_GET_MAX
@ UVC_GET_MAX
Definition: uvc-types.h:130
librealsense::platform::D3
@ D3
Definition: platform/uvc-device.h:57
librealsense::platform::v4l_uvc_meta_device::streamon
void streamon() const
Definition: backend-v4l2.cpp:2301
rmse.crop
list crop
Definition: rmse.py:129
librealsense::platform::v4l2_video_md_syncer::enqueue_front_buffer_before_throwing_it
void enqueue_front_buffer_before_throwing_it(std::queue< sync_buffer > &sync_queue)
Definition: backend-v4l2.cpp:2964
librealsense::platform::v4l_uvc_meta_device::allocate_io_buffers
void allocate_io_buffers(size_t num)
Definition: backend-v4l2.cpp:2352
librealsense::platform::v4l_uvc_meta_device::is_platform_jetson
bool is_platform_jetson() const override
Definition: backend-v4l2.h:448
librealsense::platform::usb_enumerator::query_devices_info
static std::vector< usb_device_info > query_devices_info()
Definition: enumerator-libusb.cpp:80
librealsense::platform::v4l_uvc_device::device::cap
struct v4l2_capability cap
Definition: backend-v4l2.h:424
librealsense::platform::v4l_uvc_device::signal_stop
void signal_stop()
Definition: backend-v4l2.cpp:1335
librealsense::platform::frame_callback
std::function< void(stream_profile, frame_object, std::function< void() >) > frame_callback
Definition: platform/uvc-device.h:80
uint32_t
unsigned int uint32_t
Definition: stdint.h:80
librealsense::platform::named_mutex::_device_path
std::string _device_path
Definition: backend-v4l2.h:111
librealsense::val_in_range
bool val_in_range(const T &val, const std::initializer_list< T > &list)
Definition: src/types.h:66
librealsense::platform::v4l_uvc_device::_max_fd
int _max_fd
Definition: backend-v4l2.h:428
RS_CAMERA_DEPTH_CALIBRATION_TABLE_GET
constexpr uint32_t RS_CAMERA_DEPTH_CALIBRATION_TABLE_GET
Definition: backend-v4l2.cpp:71
librealsense::platform::buffers_mgr::set_md_from_video_node
void set_md_from_video_node(bool compressed)
Definition: backend-v4l2.cpp:442
UVC_GET_LEN
@ UVC_GET_LEN
Definition: uvc-types.h:132
backend-hid.h
librealsense::platform::named_mutex::_dev_mutex
static std::map< std::string, std::recursive_mutex > _dev_mutex
Definition: backend-v4l2.h:115
librealsense::platform::uvc_device_info::uvc_capabilities
uint32_t uvc_capabilities
Definition: uvc-device-info.h:26
librealsense::platform::v4l_mipi_device::get_pu
bool get_pu(rs2_option opt, int32_t &value) const override
Definition: backend-v4l2.cpp:2572
librealsense::platform::buffer::_use_memory_map
bool _use_memory_map
Definition: backend-v4l2.h:150
librealsense::platform::RS_LASER_POWER
const uint8_t RS_LASER_POWER
Definition: backend-v4l2.cpp:2561
librealsense::platform::v4l_mipi_device::get_xu
bool get_xu(const extension_unit &xu, uint8_t control, uint8_t *data, int size) const override
Definition: backend-v4l2.cpp:2642
librealsense::platform::v4l_uvc_device::set_power_state
void set_power_state(power_state state) override
Definition: backend-v4l2.cpp:1759
height
GLint GLsizei GLsizei height
Definition: glad/glad/glad.h:1397
librealsense::platform::v4l_uvc_device::upload_video_and_metadata_from_syncer
void upload_video_and_metadata_from_syncer(buffers_mgr &buf_mgr)
Definition: backend-v4l2.cpp:1671
librealsense::platform::v4l_uvc_device::streamoff
virtual void streamoff() const override
Definition: backend-v4l2.cpp:2108
buffers
const GLuint * buffers
Definition: glad/glad/glad.h:2725
librealsense::platform::v4l_uvc_meta_device::map_device_descriptor
void map_device_descriptor()
Definition: backend-v4l2.cpp:2376
librealsense::platform::RS_HARDWARE_PRESET
const uint8_t RS_HARDWARE_PRESET
Definition: backend-v4l2.cpp:2562
librealsense::platform::create_backend
std::shared_ptr< backend > create_backend()
Definition: rsusb-backend-android.cpp:11
test-metadata.profile
profile
Definition: dds/test-metadata.py:152
librealsense::platform::v4l_uvc_device::_callback
frame_callback _callback
Definition: backend-v4l2.h:415
librealsense::platform::usb_name_to_spec
static const std::map< std::string, usb_spec > usb_name_to_spec
Definition: usb-types.h:124
V4L2_META_FMT_UVC
#define V4L2_META_FMT_UVC
Definition: backend-v4l2.h:54
librealsense::platform::get_dev_capabilities
static v4l2_capability get_dev_capabilities(const std::string dev_name)
Definition: backend-v4l2.cpp:531
librealsense::platform::buffer::_must_enqueue
bool _must_enqueue
Definition: backend-v4l2.h:154
RS2_OPTION_HUE
@ RS2_OPTION_HUE
Definition: rs_option.h:34
value
GLfloat value
Definition: glad/glad/glad.h:2099
librealsense::platform::buffers_mgr
Definition: backend-v4l2.h:201
librealsense::platform::v4l_uvc_device::unlock
void unlock() const override
Definition: backend-v4l2.cpp:2052
uint64_t
unsigned __int64 uint64_t
Definition: stdint.h:90
i
int i
Definition: rs-pcl-color.cpp:54
librealsense::platform::v4l2_video_md_syncer::pull_video_with_metadata
bool pull_video_with_metadata(std::shared_ptr< v4l2_buffer > &video_buffer, std::shared_ptr< v4l2_buffer > &md_buffer, int &video_fd, int &md_fd)
Definition: backend-v4l2.cpp:2869
librealsense::platform::extension_unit
Definition: platform/uvc-device.h:46
librealsense::metadata_hid_raw::report_type
md_hid_report report_type
Definition: src/metadata.h:810
librealsense::platform::v4l_uvc_device::_frame_drop_monitor
frame_drop_monitor _frame_drop_monitor
Definition: backend-v4l2.h:432
librealsense::platform::buffer::buffer
buffer(int fd, v4l2_buf_type type, bool use_memory_map, uint32_t index)
Definition: backend-v4l2.cpp:292
RS2_OPTION_SATURATION
@ RS2_OPTION_SATURATION
Definition: rs_option.h:35
librealsense::platform::v4l_mipi_device::set_metadata_attributes
void set_metadata_attributes(buffers_mgr &buf_mgr, __u32 bytesused, uint8_t *md_start) override
Definition: backend-v4l2.cpp:1736
RS_CAMERA_COEFF_CALIBRATION_TABLE_SET
constexpr uint32_t RS_CAMERA_COEFF_CALIBRATION_TABLE_SET
Definition: backend-v4l2.cpp:74
find_librs_version.minor
minor
Definition: find_librs_version.py:23
librealsense::platform::stream_profile::format
uint32_t format
Definition: platform/stream-profile.h:22
librealsense::platform::D0
@ D0
Definition: platform/uvc-device.h:56
librealsense::monotonic_to_realtime
double monotonic_to_realtime(double monotonic)
Definition: backend.cpp:54
librealsense::platform::v4l_uvc_device::_state
power_state _state
Definition: backend-v4l2.h:407
librealsense::platform::v4l_uvc_device::get_video_buffer
virtual std::shared_ptr< buffer > get_video_buffer(__u32 index) const
Definition: backend-v4l2.h:404
librealsense::platform::power_state
power_state
Definition: platform/uvc-device.h:54
librealsense::platform::v4l_uvc_device::start_callbacks
void start_callbacks() override
Definition: backend-v4l2.cpp:1297
unit-test-config.st
st
Definition: unit-test-config.py:343
librealsense::platform::v4l_backend::query_usb_devices
std::vector< usb_device_info > query_usb_devices() const override
Definition: backend-v4l2.cpp:2789
timercmp_lt
#define timercmp_lt(a, b)
realdds::topics::reply::key::control
const std::string control
RS_CAMERA_CID_WHITE_BALANCE_MODE
constexpr uint32_t RS_CAMERA_CID_WHITE_BALANCE_MODE
Definition: backend-v4l2.cpp:90
librealsense::platform::v4l_uvc_device::_use_memory_map
bool _use_memory_map
Definition: backend-v4l2.h:427
librealsense::platform::v4l_hid_device::foreach_hid_device
static void foreach_hid_device(std::function< void(const hid_device_info &)> action)
Definition: backend-hid.cpp:1215
librealsense::platform::control_range
Definition: platform/uvc-device.h:83
librealsense::platform::buffer::get_length_frame_only
uint32_t get_length_frame_only() const
Definition: backend-v4l2.h:138
devices.action
action
Definition: third-party/realdds/scripts/devices.py:6
opencv_pointcloud_viewer.state
state
Definition: opencv_pointcloud_viewer.py:63
test-projection-from-recording.dev
dev
Definition: test-projection-from-recording.py:17
test-shorten-json.ss
string ss
Definition: test-shorten-json.py:119
rs2_option
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls,...
Definition: rs_option.h:26
librealsense::platform::v4l_uvc_device::stream_on
void stream_on(std::function< void(const notification &n)> error_handler) override
Definition: backend-v4l2.cpp:1257
librealsense::platform::v4l_uvc_device::device::buf_type
enum v4l2_buf_type buf_type
Definition: backend-v4l2.h:422
librealsense::platform::RS_ASIC_AND_PROJECTOR_TEMPERATURES
const uint8_t RS_ASIC_AND_PROJECTOR_TEMPERATURES
Definition: backend-v4l2.cpp:2565
backend.h
librealsense::platform::v4l_uvc_device::streamon
virtual void streamon() const override
Definition: backend-v4l2.cpp:2103
librealsense::platform::req_io_buff
void req_io_buff(int fd, uint32_t count, std::string dev_name, v4l2_memory mem_type, v4l2_buf_type type)
Definition: backend-v4l2.cpp:565
librealsense::platform::frame_object
Definition: frame-object.h:16
librealsense::platform::v4l_mipi_device::xu_to_cid
uint32_t xu_to_cid(const extension_unit &xu, uint8_t control) const
Definition: backend-v4l2.cpp:2732
name
GLuint const GLchar * name
Definition: glad/glad/glad.h:2777
librealsense::platform::v4l_uvc_device::_stop_pipe_fd
int _stop_pipe_fd[2]
Definition: backend-v4l2.h:436
opencv_pointcloud_viewer.now
now
Definition: opencv_pointcloud_viewer.py:314
signal.h
UVC_GET_MIN
@ UVC_GET_MIN
Definition: uvc-types.h:129
uvc_meta_buffer::ns
__u64 ns
Definition: backend-v4l2.h:79
fps.tries
int tries
Definition: fps.py:96
MAX_DEV_PARENT_DIR
const size_t MAX_DEV_PARENT_DIR
Definition: backend-v4l2.cpp:63
librealsense::platform::buffers_mgr::md_node_present
bool md_node_present() const
Definition: backend-v4l2.cpp:496
librealsense::platform::v4l2_video_md_syncer::sync_buffer::_fd
int _fd
Definition: backend-v4l2.h:265
RS2_OPTION_EXPOSURE
@ RS2_OPTION_EXPOSURE
Definition: rs_option.h:31
RS_CAMERA_CID_PRESET
constexpr uint32_t RS_CAMERA_CID_PRESET
Definition: backend-v4l2.cpp:91
librealsense::platform::v4l_uvc_device::_dev
struct librealsense::platform::v4l_uvc_device::device _dev
librealsense::platform::v4l_uvc_device::has_metadata
virtual bool has_metadata() const override
Definition: backend-v4l2.cpp:2098
librealsense::platform::v4l_uvc_device::is_metadata_streamed
virtual bool is_metadata_streamed() const
Definition: backend-v4l2.h:403
fps
Definition: fps.py:1
librealsense::platform::buffers_mgr::get_buffers
std::array< kernel_buf_guard, e_max_kernel_buf_type > & get_buffers()
Definition: backend-v4l2.h:226
fps.info
info
Definition: fps.py:50
librealsense::platform::named_mutex::_fildes
int _fildes
Definition: backend-v4l2.h:113
librealsense::platform::e_metadata_buf
@ e_metadata_buf
Definition: backend-v4l2.h:160
librealsense::platform::stream_off
void stream_off(int fd, v4l2_buf_type type=V4L2_BUF_TYPE_VIDEO_CAPTURE)
Definition: backend-v4l2.cpp:559
librealsense::hid_header_size
constexpr uint8_t hid_header_size
Definition: src/metadata.h:803
librealsense::platform::v4l_backend::create_uvc_device
std::shared_ptr< uvc_device > create_uvc_device(uvc_device_info info) const override
Definition: backend-v4l2.cpp:2759
int64_t
signed __int64 int64_t
Definition: stdint.h:89
librealsense::platform::buffer::_original_length
uint32_t _original_length
Definition: backend-v4l2.h:148
librealsense::platform::v4l_uvc_device::map_device_descriptor
virtual void map_device_descriptor() override
Definition: backend-v4l2.cpp:2139
librealsense::platform::v4l_backend::create_device_watcher
std::shared_ptr< device_watcher > create_device_watcher() const override
Definition: backend-v4l2.cpp:2809
librealsense::platform::v4l_uvc_device::prepare_capture_buffers
virtual void prepare_capture_buffers() override
Definition: backend-v4l2.cpp:1277
RS2_OPTION_LASER_POWER
@ RS2_OPTION_LASER_POWER
Definition: rs_option.h:41
RS2_OPTION_POWER_LINE_FREQUENCY
@ RS2_OPTION_POWER_LINE_FREQUENCY
Definition: rs_option.h:50
librealsense::platform::named_mutex::acquire
void acquire()
Definition: backend-v4l2.cpp:220
RS2_OPTION_GAMMA
@ RS2_OPTION_GAMMA
Definition: rs_option.h:33
librealsense::platform::buffers_mgr::_md_start
void * _md_start
Definition: backend-v4l2.h:230
librealsense::notification
Definition: notification.h:14
LOG_DEBUG_V4L
#define LOG_DEBUG_V4L(...)
Definition: backend-v4l2.h:70
RS_CAMERA_CID_GVD
constexpr uint32_t RS_CAMERA_CID_GVD
Definition: backend-v4l2.cpp:76
DEFAULT_KPI_FRAME_DROPS_PERCENTAGE
const double DEFAULT_KPI_FRAME_DROPS_PERCENTAGE
Definition: backend-v4l2.cpp:64
librealsense::platform::name
@ name
Definition: platform/hid-device.h:63
librealsense::platform::buffer::prepare_for_streaming
void prepare_for_streaming(int fd)
Definition: backend-v4l2.cpp:336
RS_CAMERA_COEFF_CALIBRATION_TABLE_GET
constexpr uint32_t RS_CAMERA_COEFF_CALIBRATION_TABLE_GET
Definition: backend-v4l2.cpp:73
librealsense::platform::named_mutex::named_mutex
named_mutex(const std::string &device_path, unsigned timeout)
Definition: backend-v4l2.cpp:164
librealsense::platform::v4l_uvc_device::device::cropcap
struct v4l2_cropcap cropcap
Definition: backend-v4l2.h:425
librealsense::platform::v4l_uvc_device::~v4l_uvc_device
virtual ~v4l_uvc_device() override
Definition: backend-v4l2.cpp:1170
librealsense::platform::v4l_uvc_device::get_cid
virtual uint32_t get_cid(rs2_option option) const
Definition: backend-v4l2.cpp:2057
RS2_OPTION_BRIGHTNESS
@ RS2_OPTION_BRIGHTNESS
Definition: rs_option.h:29
librealsense::platform::usb_undefined
@ usb_undefined
Definition: usb-types.h:113
librealsense::platform::named_mutex::try_lock
bool try_lock()
Definition: backend-v4l2.cpp:203
librealsense::platform::v4l_uvc_device::get_profiles
std::vector< stream_profile > get_profiles() const override
Definition: backend-v4l2.cpp:1960
assert
#define assert(condition)
Definition: lz4.c:245
test-color_frame_frops.fps
int fps
Definition: test-color_frame_frops.py:16
librealsense::platform::v4l2_video_md_syncer::_video_queue
std::queue< sync_buffer > _video_queue
Definition: backend-v4l2.h:288
librealsense::platform::v4l_uvc_device::unmap_device_descriptor
virtual void unmap_device_descriptor() override
Definition: backend-v4l2.cpp:2198
librealsense::platform::v4l_uvc_device::_is_started
std::atomic< bool > _is_started
Definition: backend-v4l2.h:418
hid-data.h
librealsense::platform::buffer
Definition: backend-v4l2.h:122
rsutils::string::from
Definition: from.h:19
librealsense::platform::e_video_buf
@ e_video_buf
Definition: backend-v4l2.h:159
librealsense::platform::v4l_uvc_meta_device::streamoff
void streamoff() const
Definition: backend-v4l2.cpp:2322
RS_CAMERA_CID_BASE
constexpr uint32_t RS_CAMERA_CID_BASE
Definition: backend-v4l2.cpp:68
backend-v4l2.h
int32_t
signed int int32_t
Definition: stdint.h:77
RS_STREAM_CONFIG_0
constexpr uint32_t RS_STREAM_CONFIG_0
Definition: backend-v4l2.cpp:67
p
double p[GRIDW][GRIDH]
Definition: wave.c:109
librealsense::platform::v4l_uvc_device::acquire_metadata
virtual void acquire_metadata(buffers_mgr &buf_mgr, fd_set &fds, bool compressed_format=false) override
Definition: backend-v4l2.cpp:1751
std::stoi
int stoi(const std::string &value)
Definition: android_helpers.h:42
librealsense::platform::buffers_mgr::request_next_frame
void request_next_frame()
Definition: backend-v4l2.cpp:430
librealsense::platform::v4l_uvc_device::_is_capturing
std::atomic< bool > _is_capturing
Definition: backend-v4l2.h:416
librealsense::option
Definition: option-interface.h:22
RS_CAMERA_CID_EWB
constexpr uint32_t RS_CAMERA_CID_EWB
Definition: backend-v4l2.cpp:82
librealsense::platform::v4l_uvc_device::_profile
stream_profile _profile
Definition: backend-v4l2.h:414
RS2_OPTION_EMITTER_ENABLED
@ RS2_OPTION_EMITTER_ENABLED
Definition: rs_option.h:46
librealsense::big_endian
Definition: src/types.h:78
RS2_OPTION_AUTO_EXPOSURE_PRIORITY
@ RS2_OPTION_AUTO_EXPOSURE_PRIORITY
Definition: rs_option.h:58
first
GLint first
Definition: glad/glad/glad.h:2301
librealsense::platform::uvc_device::_error_handler
std::function< void(const notification &n) > _error_handler
Definition: platform/uvc-device.h:152
range
GLsizei range
Definition: glad/glad/glad.h:1535
librealsense::platform::v4l_mipi_device::get_pu_range
control_range get_pu_range(rs2_option option) const override
Definition: backend-v4l2.cpp:2702
sort
void sort(sort_type m_sort_type, const std::string &in, const std::string &out)
Definition: rs-rosbag-inspector.cpp:350
librealsense::platform::v4l_uvc_device::set_xu
bool set_xu(const extension_unit &xu, uint8_t control, const uint8_t *data, int size) override
Definition: backend-v4l2.cpp:1773
librealsense::platform::v4l_uvc_meta_device::_md_fd
int _md_fd
Definition: backend-v4l2.h:464
state
Definition: rs-measure.cpp:80
librealsense::platform::v4l2_video_md_syncer::_is_ready
bool _is_ready
Definition: backend-v4l2.h:290
librealsense::platform::RS_EMITTER_FREQUENCY
const uint8_t RS_EMITTER_FREQUENCY
Definition: backend-v4l2.cpp:2569
librealsense::linux_backend_exception
Definition: librealsense-exception.h:87
V4L2_META_FMT_D4XX
#define V4L2_META_FMT_D4XX
Definition: backend-v4l2.h:63
librealsense::platform::v4l_uvc_meta_device::~v4l_uvc_meta_device
virtual ~v4l_uvc_meta_device()
Definition: backend-v4l2.cpp:2297
librealsense::platform::v4l_uvc_device::get_xu_range
control_range get_xu_range(const extension_unit &xu, uint8_t control, int len) const override
Definition: backend-v4l2.cpp:1802
librealsense::platform::v4l_uvc_device::foreach_uvc_device
static void foreach_uvc_device(std::function< void(const uvc_device_info &, const std::string &)> action)
Definition: backend-v4l2.cpp:912
librealsense::platform::RS_ERROR_REPORTING
const uint8_t RS_ERROR_REPORTING
Definition: backend-v4l2.cpp:2563
RS2_OPTION_SHARPNESS
@ RS2_OPTION_SHARPNESS
Definition: rs_option.h:36
librealsense::platform::buffer::_start
uint8_t * _start
Definition: backend-v4l2.h:146
librealsense::platform::buffer::attach_buffer
void attach_buffer(const v4l2_buffer &buf)
Definition: backend-v4l2.cpp:371
librealsense::platform::v4l_backend::create_usb_device
std::shared_ptr< command_transfer > create_usb_device(usb_device_info info) const override
Definition: backend-v4l2.cpp:2781
librealsense::platform::v4l_backend::query_hid_devices
std::vector< hid_device_info > query_hid_devices() const override
Definition: backend-v4l2.cpp:2800
rmse.e
e
Definition: rmse.py:177
librealsense::platform::buffers_mgr::metadata_start
void * metadata_start() const
Definition: backend-v4l2.h:218
librealsense::platform::v4l2_video_md_syncer::push_metadata
void push_metadata(const sync_buffer &md_buffer)
Definition: backend-v4l2.cpp:2842
librealsense::platform::buffer::get_full_length
uint32_t get_full_length() const
Definition: backend-v4l2.h:137
librealsense::platform::named_mutex::_dev_mutex_cnt
static std::map< std::string, int > _dev_mutex_cnt
Definition: backend-v4l2.h:116
usb-enumerator.h
librealsense::platform::v4l_uvc_device::device::num_planes
unsigned char num_planes
Definition: backend-v4l2.h:423
rs2::textual_icons::lock
static const textual_icon lock
Definition: device-model.h:186
librealsense::platform::v4l2_video_md_syncer::flush_queues
void flush_queues()
Definition: backend-v4l2.cpp:2982
librealsense::metadata_imu_report_size
constexpr uint8_t metadata_imu_report_size
Definition: src/metadata.h:772
librealsense::platform::v4l_backend::create_hid_device
std::shared_ptr< hid_device > create_hid_device(hid_device_info info) const override
Definition: backend-v4l2.cpp:2795
UVC_SET_CUR
@ UVC_SET_CUR
Definition: uvc-types.h:127
RS_CAMERA_CID_AE_ROI_SET
constexpr uint32_t RS_CAMERA_CID_AE_ROI_SET
Definition: backend-v4l2.cpp:78
librealsense::platform::v4l_uvc_meta_device::acquire_metadata
virtual void acquire_metadata(buffers_mgr &buf_mgr, fd_set &fds, bool compressed_format=false)
Definition: backend-v4l2.cpp:2502
librealsense::platform::extension_unit::unit
uint8_t unit
Definition: platform/uvc-device.h:49
librealsense::platform::buffer::_index
uint32_t _index
Definition: backend-v4l2.h:151
librealsense::platform::v4l2_video_md_syncer::_syncer_mutex
std::mutex _syncer_mutex
Definition: backend-v4l2.h:287
UVC_GET_RES
@ UVC_GET_RES
Definition: uvc-types.h:131
RS_CAMERA_CID_EMITTER_FREQUENCY
constexpr uint32_t RS_CAMERA_CID_EMITTER_FREQUENCY
Definition: backend-v4l2.cpp:92
it
static auto it
Definition: openvino-face-detection.cpp:375
librealsense::platform::buffer::use_memory_map
bool use_memory_map() const
Definition: backend-v4l2.h:142
librealsense::platform::RS_HWMONITOR
const uint8_t RS_HWMONITOR
Definition: backend-v4l2.cpp:2558
test-depth.result
result
Definition: test-depth.py:183
UVC_GET_DEF
@ UVC_GET_DEF
Definition: uvc-types.h:134
librealsense::platform::v4l_uvc_device::lock
void lock() const override
Definition: backend-v4l2.cpp:2048
librealsense::platform::usb_enumerator::create_usb_device
static rs_usb_device create_usb_device(const usb_device_info &info)
Definition: enumerator-libusb.cpp:105
librealsense::platform::buffer::request_next_frame
void request_next_frame(int fd, bool force=false)
Definition: backend-v4l2.cpp:384
s
GLdouble s
Definition: glad/glad/glad.h:2441
RS_CAMERA_CID_LASER_POWER_MODE
constexpr uint32_t RS_CAMERA_CID_LASER_POWER_MODE
Definition: backend-v4l2.cpp:86
librealsense::platform::stream_ctl_on
void stream_ctl_on(int fd, v4l2_buf_type type=V4L2_BUF_TYPE_VIDEO_CAPTURE)
Definition: backend-v4l2.cpp:553
librealsense::platform::v4l2_video_md_syncer::sync_buffer
Definition: backend-v4l2.h:262
librealsense::platform::stream_profile
Definition: platform/stream-profile.h:17
librealsense::platform::buffer::detach_buffer
void detach_buffer()
Definition: backend-v4l2.cpp:378
timeout
GLbitfield GLuint64 timeout
Definition: glad/glad/glad.h:3384
find_librs_version.major
major
Definition: find_librs_version.py:18
librealsense::platform::uvc_device_info
Definition: uvc-device-info.h:15
librealsense::platform::v4l_uvc_device::set_pu
bool set_pu(rs2_option opt, int32_t value) override
Definition: backend-v4l2.cpp:1895
LOG_INFO
LOG_INFO("Log message using LOG_INFO()")
librealsense::platform::v4l_mipi_device::set_pu
bool set_pu(rs2_option opt, int32_t value) override
Definition: backend-v4l2.cpp:2593
RS2_NOTIFICATION_CATEGORY_UNKNOWN_ERROR
@ RS2_NOTIFICATION_CATEGORY_UNKNOWN_ERROR
Definition: rs_types.h:22
buf
GLenum GLuint GLenum GLsizei const GLchar * buf
Definition: glad/glad/glad.h:3610
test-hdr-long.pipe
pipe
Definition: test-hdr-long.py:88
librealsense::platform::RS_LED_PWR
const uint8_t RS_LED_PWR
Definition: backend-v4l2.cpp:2568
librealsense::platform::buffer::_length
uint32_t _length
Definition: backend-v4l2.h:147
librealsense::hid_header::length
uint8_t length
Definition: src/metadata.h:797
profile
Definition: unit-tests-common.h:58
rmse.d
d
Definition: rmse.py:171
RS2_NOTIFICATION_CATEGORY_FRAME_CORRUPTED
@ RS2_NOTIFICATION_CATEGORY_FRAME_CORRUPTED
Definition: rs_types.h:19
rs2::textual_icons::usb_type
static const textual_icon usb_type
Definition: device-model.h:217
RS2_NOTIFICATION_CATEGORY_FRAMES_TIMEOUT
@ RS2_NOTIFICATION_CATEGORY_FRAMES_TIMEOUT
Definition: rs_types.h:18
librealsense::platform::usb_device_info
Definition: usb-types.h:146
LOG_ERROR
#define LOG_ERROR(...)
Definition: easyloggingpp.h:73
librealsense::platform::v4l_uvc_device::_named_mtx
std::unique_ptr< named_mutex > _named_mtx
Definition: backend-v4l2.h:420
librealsense::platform::buffers_mgr::set_md_attributes
void set_md_attributes(uint8_t md_size, void *md_start)
Definition: backend-v4l2.h:220
librealsense::platform::get_devname_from_video_path
bool get_devname_from_video_path(const std::string &video_path, std::string &dev_name)
Definition: backend-v4l2.cpp:581
RS2_OPTION_ENABLE_AUTO_WHITE_BALANCE
@ RS2_OPTION_ENABLE_AUTO_WHITE_BALANCE
Definition: rs_option.h:39
RS2_LOG_SEVERITY_ERROR
@ RS2_LOG_SEVERITY_ERROR
Definition: rs_types.h:125
librealsense::platform::RS_EXT_TRIGGER
const uint8_t RS_EXT_TRIGGER
Definition: backend-v4l2.cpp:2564


librealsense2
Author(s): LibRealSense ROS Team
autogenerated on Mon Apr 22 2024 02:12:55