backend-v4l2.h
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 #pragma once
5 
6 #include "backend.h"
7 #include "types.h"
8 
9 #include <cassert>
10 #include <cstdlib>
11 #include <cstdio>
12 #include <cstring>
13 
14 #include <algorithm>
15 #include <array>
16 #include <functional>
17 #include <string>
18 #include <sstream>
19 #include <fstream>
20 #include <regex>
21 #include <thread>
22 #include <utility> // for pair
23 #include <chrono>
24 #include <thread>
25 #include <atomic>
26 
27 #include <dirent.h>
28 #include <fcntl.h>
29 #include <unistd.h>
30 #include <limits.h>
31 #include <cmath>
32 #include <errno.h>
33 #include <sys/stat.h>
34 #include <sys/mman.h>
35 #include <sys/ioctl.h>
36 #include <linux/usb/video.h>
37 #include <linux/uvcvideo.h>
38 #include <linux/videodev2.h>
39 #include <regex>
40 #include <list>
41 
42 // Metadata streaming nodes are available with kernels 4.16+
43 #ifdef V4L2_META_FMT_UVC
44 constexpr bool metadata_node = true;
45 #else
46 #pragma message ( "\nLibrealsense notification: V4L2_META_FMT_UVC was not defined, adding metadata constructs")
47 
48 constexpr bool metadata_node = false;
49 
50 // Providing missing parts from videodev2.h
51 // V4L2_META_FMT_UVC >> V4L2_CAP_META_CAPTURE is also defined, but the opposite does not hold
52 #define V4L2_META_FMT_UVC v4l2_fourcc('U', 'V', 'C', 'H') /* UVC Payload Header */
53 
54 #ifndef V4L2_CAP_META_CAPTURE
55 #define V4L2_CAP_META_CAPTURE 0x00800000 /* Specified in kernel header v4.16 */
56 #endif // V4L2_CAP_META_CAPTURE
57 
58 #endif // V4L2_META_FMT_UVC
59 
60 #ifndef V4L2_META_FMT_D4XX
61 #define V4L2_META_FMT_D4XX v4l2_fourcc('D', '4', 'X', 'X') /* D400 Payload Header metadata */
62 #endif
63 
64 #undef DEBUG_V4L
65 #ifdef DEBUG_V4L
66 #define LOG_DEBUG_V4L(...) do { CLOG(DEBUG ,"librealsense") << __VA_ARGS__; } while(false)
67 #else
68 #define LOG_DEBUG_V4L(...)
69 #endif //DEBUG_V4L
70 
71 // Use local definition of buf type to resolve for kernel versions
72 constexpr auto LOCAL_V4L2_BUF_TYPE_META_CAPTURE = (v4l2_buf_type)(13);
73 
74 #pragma pack(push, 1)
75 // The struct definition is identical to uvc_meta_buf defined uvcvideo.h/ kernel 4.16 headers, and is provided to allow for cross-kernel compilation
77  __u64 ns; // system timestamp of the payload in nanoseconds
78  __u16 sof; // USB Frame Number
79  __u8 length; // length of the payload metadata header
80  __u8 flags; // payload header flags
81  __u8* buf; //device-specific metadata payload data
82 };
83 #pragma pack(pop)
84 
85 
86 namespace librealsense
87 {
88  namespace platform
89  {
91  {
92  public:
93  named_mutex(const std::string& device_path, unsigned timeout);
94 
95  named_mutex(const named_mutex&) = delete;
96 
97  ~named_mutex();
98 
99  void lock();
100 
101  void unlock();
102 
103  bool try_lock();
104 
105  private:
106  void acquire();
107  void release();
108 
109  std::string _device_path;
111  int _fildes;
112  static std::recursive_mutex _init_mutex;
113  static std::map<std::string, std::recursive_mutex> _dev_mutex;
114  static std::map<std::string, int> _dev_mutex_cnt;
116  std::mutex _mutex;
117  };
118  static int xioctl(int fh, unsigned long request, void *arg);
119 
120  class buffer
121  {
122  public:
123  buffer(int fd, v4l2_buf_type type, bool use_memory_map, uint32_t index);
124 
125  void prepare_for_streaming(int fd);
126 
127  ~buffer();
128 
129  void attach_buffer(const v4l2_buffer& buf);
130 
131  void detach_buffer();
132 
133  void request_next_frame(int fd, bool force=false);
134 
135  uint32_t get_full_length() const { return _length; }
136  uint32_t get_length_frame_only() const { return _original_length; }
137 
138  uint8_t* get_frame_start() const { return _start; }
139 
140  bool use_memory_map() const { return _use_memory_map; }
141 
142  private:
143  v4l2_buf_type _type;
149  v4l2_buffer _buf;
150  std::mutex _mutex;
151  bool _must_enqueue = false;
152  };
153 
155  {
159  };
160 
161 
162  // RAII for buffer exchange with kernel
164  {
166  {
167  if (_data_buf && (!_managed))
168  {
169  if (_file_desc > 0)
170  {
171  if (xioctl(_file_desc, (int)VIDIOC_QBUF, &_dq_buf) < 0)
172  {
173  LOG_DEBUG_V4L("xioctl(VIDIOC_QBUF) guard failed for fd " << std::dec << _file_desc);
174  if (xioctl(_file_desc, (int)VIDIOC_DQBUF, &_dq_buf) >= 0)
175  {
176  LOG_DEBUG_V4L("xioctl(VIDIOC_QBUF) Re-enqueue succeeded for fd " << std::dec << _file_desc);
177  if (xioctl(_file_desc, (int)VIDIOC_QBUF, &_dq_buf) < 0)
178  LOG_DEBUG_V4L("xioctl(VIDIOC_QBUF) re-deque failed for fd " << std::dec << _file_desc);
179  else
180  LOG_DEBUG_V4L("xioctl(VIDIOC_QBUF) re-deque succeeded for fd " << std::dec << _file_desc);
181  }
182  else
183  LOG_DEBUG_V4L("xioctl(VIDIOC_QBUF) Re-enqueue failed for fd " << std::dec << _file_desc);
184  }
185  else
186  LOG_DEBUG_V4L("Enqueue (e) buf " << std::dec << _dq_buf.index << " for fd " << _file_desc);
187  }
188  }
189  }
190 
191  std::shared_ptr<platform::buffer> _data_buf=nullptr;
192  v4l2_buffer _dq_buf{};
193  int _file_desc=-1;
194  bool _managed=false;
195  };
196 
197  // RAII handling of kernel buffers interchanges
199  {
200  public:
201  buffers_mgr(bool memory_mapped_buf) :
202  _md_start(nullptr),
203  _md_size(0),
204  _mmap_bufs(memory_mapped_buf)
205  {}
206 
208 
209  void request_next_frame();
210  void handle_buffer(supported_kernel_buf_types buf_type, int file_desc,
211  v4l2_buffer buf= v4l2_buffer(),
212  std::shared_ptr<platform::buffer> data_buf=nullptr);
213 
214  uint8_t metadata_size() const { return _md_size; }
215  void* metadata_start() const { return _md_start; }
216 
217  void set_md_attributes(uint8_t md_size, void* md_start)
218  { _md_start = md_start; _md_size = md_size; }
219  void set_md_from_video_node(bool compressed);
220  bool verify_vd_md_sync() const;
221  bool md_node_present() const;
222 
223  std::array<kernel_buf_guard, e_max_kernel_buf_type>& get_buffers()
224  { return buffers; }
225 
226  private:
227  void* _md_start; // marks the address of metadata blob
228  uint8_t _md_size; // metadata size is bounded by 255 bytes by design
230 
231 
232  std::array<kernel_buf_guard, e_max_kernel_buf_type> buffers;
233  };
234 
236  {
237  virtual void capture_loop() = 0;
238 
239  virtual bool has_metadata() const = 0;
240 
241  virtual void streamon() const = 0;
242  virtual void streamoff() const = 0;
243  virtual void negotiate_kernel_buffers(size_t num) const = 0;
244 
245  virtual void allocate_io_buffers(size_t num) = 0;
246  virtual void map_device_descriptor() = 0;
247  virtual void unmap_device_descriptor() = 0;
248  virtual void set_format(stream_profile profile) = 0;
249  virtual void prepare_capture_buffers() = 0;
250  virtual void stop_data_capture() = 0;
251  virtual void acquire_metadata(buffers_mgr & buf_mgr,fd_set &fds, bool compressed_format) = 0;
252  };
253 
255  {
256  public:
257  v4l2_video_md_syncer() : _is_ready(false){}
258 
259  struct sync_buffer
260  {
261  std::shared_ptr<v4l2_buffer> _v4l2_buf;
262  int _fd;
264  };
265 
266  // pushing video buffer to the video queue
267  void push_video(const sync_buffer& video_buffer);
268  // pushing metadata buffer to the metadata queue
269  void push_metadata(const sync_buffer& md_buffer);
270 
271  // pulling synced data
272  // if returned value is true - the data could have been pulled
273  // if returned value is false - no data is returned via the inout params because data could not be synced
274  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);
275 
276  inline void start() {_is_ready = true;}
277  void stop();
278 
279  private:
280  void enqueue_buffer_before_throwing_it(const sync_buffer& sb) const;
281  void enqueue_front_buffer_before_throwing_it(std::queue<sync_buffer>& sync_queue);
282  void flush_queues();
283 
284  std::mutex _syncer_mutex;
285  std::queue<sync_buffer> _video_queue;
286  std::queue<sync_buffer> _md_queue;
287  bool _is_ready;
288  };
289 
290  // The aim of the frame_drop_monitor is to check the frames drops kpi - which requires
291  // that no more than some percentage of the frames are dropped
292  // It is checked using the fps, and the previous corrupted frames, on the last 30 seconds
293  // for example, for frame rate of 30 fps, and kpi of 5%, the criteria will be:
294  // if at least 45 frames (= 30[fps] * 5%[kpi]* 30[sec]) drops have occured in the previous 30 seconds,
295  // then the kpi is violated
297  {
298  public:
299  frame_drop_monitor(double kpi_frames_drops_percentage) : _kpi_frames_drops_pct(kpi_frames_drops_percentage) {}
300  // update_and_check_kpi method returns whether the kpi has been violated
301  // it should be called each time a partial frame is caught
302  bool update_and_check_kpi(const stream_profile& profile, const timeval& timestamp);
303 
304  private:
305  // container used to store the latest timestamps of the partial frames, per profile
306  std::vector<std::pair<stream_profile, std::deque<long int>>> drops_per_stream;
308  };
309 
311  {
312  public:
313  static void foreach_uvc_device(
314  std::function<void(const uvc_device_info&,
315  const std::string&)> action);
316 
317  static std::vector<std::string> get_video_paths();
318 
319  static bool is_usb_path_valid(const std::string& usb_video_path, const std::string &dev_name,
320  std::string &busnum, std::string &devnum, std::string &devpath);
321 
322  static bool is_usb_device_path(const std::string& video_path);
323 
324  static uvc_device_info get_info_from_usb_device_path(const std::string& video_path, const std::string& name);
325 
326  static uvc_device_info get_info_from_mipi_device_path(const std::string& video_path, const std::string& name);
327 
328  static void get_mipi_device_info(const std::string& dev_name,
329  std::string& bus_info, std::string& card);
330 
331  v4l_uvc_device(const uvc_device_info& info, bool use_memory_map = false);
332 
333  virtual ~v4l_uvc_device() override;
334 
335  void probe_and_commit(stream_profile profile, frame_callback callback, int buffers) override;
336 
337  void stream_on(std::function<void(const notification& n)> error_handler) override;
338 
339  void start_callbacks() override;
340 
341  void stop_callbacks() override;
342 
343  void close(stream_profile) override;
344 
345  std::string fourcc_to_string(uint32_t id) const;
346 
347  void signal_stop();
348 
349  void poll();
350 
351  void set_power_state(power_state state) override;
352  power_state get_power_state() const override { return _state; }
353 
354  void init_xu(const extension_unit&) override {}
355  bool set_xu(const extension_unit& xu, uint8_t control, const uint8_t* data, int size) override;
356  bool get_xu(const extension_unit& xu, uint8_t control, uint8_t* data, int size) const override;
357  control_range get_xu_range(const extension_unit& xu, uint8_t control, int len) const override;
358 
359  bool get_pu(rs2_option opt, int32_t& value) const override;
360 
361  bool set_pu(rs2_option opt, int32_t value) override;
362 
363  control_range get_pu_range(rs2_option option) const override;
364 
365  std::vector<stream_profile> get_profiles() const override;
366 
367  void lock() const override;
368  void unlock() const override;
369 
370  std::string get_device_location() const override { return _device_path; }
371  usb_spec get_usb_specification() const override { return _device_usb_spec; }
372 
373  protected:
374  virtual uint32_t get_cid(rs2_option option) const;
375 
376  virtual void capture_loop() override;
377 
378  virtual bool has_metadata() const override;
379 
380  virtual void streamon() const override;
381  virtual void streamoff() const override;
382  virtual void negotiate_kernel_buffers(size_t num) const override;
383 
384  virtual void allocate_io_buffers(size_t num) override;
385  virtual void map_device_descriptor() override;
386  virtual void unmap_device_descriptor() override;
387  virtual void set_format(stream_profile profile) override;
388  virtual void prepare_capture_buffers() override;
389  virtual void stop_data_capture() override;
390  virtual void acquire_metadata(buffers_mgr & buf_mgr,fd_set &fds, bool compressed_format = false) override;
391  virtual void set_metadata_attributes(buffers_mgr& buf_mgr, __u32 bytesused, uint8_t* md_start);
392  void subscribe_to_ctrl_event(uint32_t control_id);
393  void unsubscribe_from_ctrl_event(uint32_t control_id);
394  bool pend_for_ctrl_status_event();
395  void upload_video_and_metadata_from_syncer(buffers_mgr& buf_mgr);
396  void populate_imu_data(metadata_hid_raw& meta_data, uint8_t* frame_start, uint8_t& md_size, void** md_start) const;
397  // checking if metadata is streamed
398  virtual inline bool is_metadata_streamed() const { return false;}
399  virtual inline std::shared_ptr<buffer> get_video_buffer(__u32 index) const {return _buffers[index];}
400  virtual inline std::shared_ptr<buffer> get_md_buffer(__u32 index) const {return nullptr;}
401 
402  power_state _state = D3;
403  std::string _name = "";
404  std::string _device_path = "";
405  usb_spec _device_usb_spec = usb_undefined;
407 
408  std::vector<std::shared_ptr<buffer>> _buffers;
411  std::atomic<bool> _is_capturing;
412  std::atomic<bool> _is_alive;
413  std::atomic<bool> _is_started;
414  std::unique_ptr<std::thread> _thread;
415  std::unique_ptr<named_mutex> _named_mtx;
417  int _max_fd = 0; // specifies the maximal pipe number the polling process will monitor
418  std::vector<int> _fds; // list the file descriptors to be monitored during frames polling
419  buffers_mgr _buf_dispatch; // Holder for partial (MD only) frames that shall be preserved between 'select' calls when polling v4l buffers
420  int _fd = 0;
421  frame_drop_monitor _frame_drop_monitor; // used to check the frames drops kpi
423 
424  private:
425  int _stop_pipe_fd[2]; // write to _stop_pipe_fd[1] and read from _stop_pipe_fd[0]
426 
427  };
428 
429  // Composition layer for uvc/metadata split nodes introduced with kernel 4.16
431  {
432  public:
433  v4l_uvc_meta_device(const uvc_device_info& info, bool use_memory_map = false);
434 
435  virtual ~v4l_uvc_meta_device();
436 
437  protected:
438 
439  void streamon() const;
440  void streamoff() const;
441  void negotiate_kernel_buffers(size_t num) const;
442  void allocate_io_buffers(size_t num);
443  void map_device_descriptor();
444  void unmap_device_descriptor();
445  void set_format(stream_profile profile);
446  void prepare_capture_buffers();
447  virtual void acquire_metadata(buffers_mgr & buf_mgr,fd_set &fds, bool compressed_format=false);
448  // checking if metadata is streamed
449  virtual inline bool is_metadata_streamed() const { return _md_fd > 0;}
450  virtual inline std::shared_ptr<buffer> get_md_buffer(__u32 index) const {return _md_buffers[index];}
451  int _md_fd = -1;
452  std::string _md_name = "";
453 
454  std::vector<std::shared_ptr<buffer>> _md_buffers;
456  };
457 
458  // D457 Development. To be merged into underlying class
460  {
461  public:
462  v4l_mipi_device(const uvc_device_info& info, bool use_memory_map = true);
463 
464  virtual ~v4l_mipi_device();
465 
466  bool get_pu(rs2_option opt, int32_t& value) const override;
467  bool set_pu(rs2_option opt, int32_t value) override;
468  bool set_xu(const extension_unit& xu, uint8_t control, const uint8_t* data, int size) override;
469  bool get_xu(const extension_unit& xu, uint8_t control, uint8_t* data, int size) const override;
470  control_range get_xu_range(const extension_unit& xu, uint8_t control, int len) const override;
471  control_range get_pu_range(rs2_option option) const override;
472  void set_metadata_attributes(buffers_mgr& buf_mgr, __u32 bytesused, uint8_t* md_start) override;
473  protected:
474  virtual uint32_t get_cid(rs2_option option) const;
475  uint32_t xu_to_cid(const extension_unit& xu, uint8_t control) const; // Find the mapping of XU to the underlying control
476  };
477 
478  class v4l_backend : public backend
479  {
480  public:
481  std::shared_ptr<uvc_device> create_uvc_device(uvc_device_info info) const override;
482  std::vector<uvc_device_info> query_uvc_devices() const override;
483 
484  std::shared_ptr<command_transfer> create_usb_device(usb_device_info info) const override;
485  std::vector<usb_device_info> query_usb_devices() const override;
486 
487  std::shared_ptr<hid_device> create_hid_device(hid_device_info info) const override;
488  std::vector<hid_device_info> query_hid_devices() const override;
489 
490  std::shared_ptr<time_service> create_time_service() const override;
491  std::shared_ptr<device_watcher> create_device_watcher() const override;
492  };
493  }
494 }
static const textual_icon lock
Definition: model-views.h:219
std::vector< std::pair< stream_profile, std::deque< long int > > > drops_per_stream
Definition: backend-v4l2.h:306
string action
Definition: devices.py:737
static const textual_icon unlock
Definition: model-views.h:238
GLuint const GLchar * name
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
Definition: rs_option.h:22
metadata_hid_raw - HID metadata structure layout populated by backend
Definition: src/metadata.h:872
uint32_t get_full_length() const
Definition: backend-v4l2.h:135
std::vector< std::shared_ptr< buffer > > _md_buffers
Definition: backend-v4l2.h:454
uint32_t get_length_frame_only() const
Definition: backend-v4l2.h:136
void init_xu(const extension_unit &) override
Definition: backend-v4l2.h:354
GLfloat value
std::array< kernel_buf_guard, e_max_kernel_buf_type > & get_buffers()
Definition: backend-v4l2.h:223
constexpr bool metadata_node
Definition: backend-v4l2.h:48
buffers_mgr(bool memory_mapped_buf)
Definition: backend-v4l2.h:201
Definition: arg_fwd.hpp:23
unsigned char uint8_t
Definition: stdint.h:78
GLenum GLfloat * buffer
static const textual_icon stop
Definition: model-views.h:226
power_state get_power_state() const override
Definition: backend-v4l2.h:352
void set_md_attributes(uint8_t md_size, void *md_start)
Definition: backend-v4l2.h:217
GLuint index
GLenum GLuint GLenum GLsizei const GLchar * buf
def info(name, value, persistent=False)
Definition: test.py:327
GLsizeiptr size
static std::map< std::string, int > _dev_mutex_cnt
Definition: backend-v4l2.h:114
unsigned int uint32_t
Definition: stdint.h:80
constexpr auto LOCAL_V4L2_BUF_TYPE_META_CAPTURE
Definition: backend-v4l2.h:72
def callback(frame)
Definition: t265_stereo.py:91
frame_drop_monitor(double kpi_frames_drops_percentage)
Definition: backend-v4l2.h:299
#define LOG_DEBUG_V4L(...)
Definition: backend-v4l2.h:68
static int xioctl(int fh, unsigned long request, void *arg)
const GLuint * buffers
virtual bool is_metadata_streamed() const
Definition: backend-v4l2.h:398
std::function< void(stream_profile, frame_object, std::function< void()>)> frame_callback
Definition: backend.h:184
static std::recursive_mutex _init_mutex
Definition: backend-v4l2.h:112
GLbitfield GLuint64 timeout
GLenum type
std::unique_ptr< named_mutex > _named_mtx
Definition: backend-v4l2.h:415
static std::map< std::string, std::recursive_mutex > _dev_mutex
Definition: backend-v4l2.h:113
std::string get_device_location() const override
Definition: backend-v4l2.h:370
virtual std::shared_ptr< buffer > get_md_buffer(__u32 index) const
Definition: backend-v4l2.h:400
usb_spec get_usb_specification() const override
Definition: backend-v4l2.h:371
signed int int32_t
Definition: stdint.h:77
std::array< kernel_buf_guard, e_max_kernel_buf_type > buffers
Definition: backend-v4l2.h:232
std::vector< std::shared_ptr< buffer > > _buffers
Definition: backend-v4l2.h:408
uint8_t * get_frame_start() const
Definition: backend-v4l2.h:138
virtual std::shared_ptr< buffer > get_video_buffer(__u32 index) const
Definition: backend-v4l2.h:399
Definition: parser.hpp:153
virtual std::shared_ptr< buffer > get_md_buffer(__u32 index) const
Definition: backend-v4l2.h:450
std::unique_ptr< std::thread > _thread
Definition: backend-v4l2.h:414


librealsense2
Author(s): LibRealSense ROS Team
autogenerated on Thu Dec 22 2022 03:41:42