backend.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 #ifndef LIBREALSENSE_BACKEND_H
6 #define LIBREALSENSE_BACKEND_H
7 
8 #include "../include/librealsense2/h/rs_types.h" // Inherit all type definitions in the public API
9 #include "../include/librealsense2/h/rs_option.h"
10 #include "usb/usb-types.h"
11 #include "usb/usb-device.h"
12 #include "hid/hid-types.h"
13 #include "command_transfer.h"
14 
15 #include <memory> // For shared_ptr
16 #include <functional> // For function
17 #include <thread> // For this_thread::sleep_for
18 #include <vector>
19 #include <algorithm>
20 #include <set>
21 #include <iterator>
22 #include <tuple>
23 #include <map>
24 #include <cstring>
25 #include <string>
26 #include <sstream>
27 #include <fstream>
28 
29 
30 const uint16_t MAX_RETRIES = 100;
33 
34 const uint8_t MAX_META_DATA_SIZE = 0xff; // UVC Metadata total length
35  // is limited by (UVC Bulk) design to 255 bytes
36 
37 namespace librealsense
38 {
39  struct notification;
40 
41  template<class T>
42  bool list_changed(const std::vector<T>& list1,
43  const std::vector<T>& list2,
44  std::function<bool(T, T)> equal = [](T first, T second) { return first == second; })
45  {
46  if (list1.size() != list2.size())
47  return true;
48 
49  for (auto dev1 : list1)
50  {
51  bool found = false;
52  for (auto dev2 : list2)
53  {
54  if (equal(dev1,dev2))
55  {
56  found = true;
57  }
58  }
59 
60  if (!found)
61  {
62  return true;
63  }
64  }
65  return false;
66  }
67 
68 
69  namespace platform
70  {
72  {
74  {}
75 
76  control_range(int32_t in_min, int32_t in_max, int32_t in_step, int32_t in_def)
77  {
78  populate_raw_data(min, in_min);
79  populate_raw_data(max, in_max);
80  populate_raw_data(step, in_step);
81  populate_raw_data(def, in_def);
82  }
83  control_range(std::vector<uint8_t> in_min, std::vector<uint8_t> in_max, std::vector<uint8_t> in_step, std::vector<uint8_t> in_def)
84  {
85  min = in_min; max = in_max; step = in_step; def = in_def;
86  }
87  std::vector<uint8_t> min;
88  std::vector<uint8_t> max;
89  std::vector<uint8_t> step;
90  std::vector<uint8_t> def;
91 
92  private:
93  void populate_raw_data(std::vector<uint8_t>& vec, int32_t value);
94  };
95 
97  {
98  public:
99  virtual double get_time() const = 0;
100  virtual ~time_service() = default;
101  };
102 
104  {
105  public:
106  rs2_time_t get_time() const override
107  {
108  return std::chrono::duration<double, std::milli>(std::chrono::system_clock::now().time_since_epoch()).count();
109  }
110  };
111 
112  struct guid { uint32_t data1; uint16_t data2, data3; uint8_t data4[8]; };
113  // subdevice and node fields are assigned by Host driver; unit and GUID are hard-coded in camera firmware
114  struct extension_unit { int subdevice; uint8_t unit; int node; guid id; };
115 
117  {
118  D0,
120  };
121 
122  typedef std::tuple< uint32_t, uint32_t, uint32_t, uint32_t> stream_profile_tuple;
123 
125  {
130 
131  operator stream_profile_tuple() const
132  {
133  return std::make_tuple(width, height, fps, format);
134  }
135 
136  };
137 
138  inline bool operator==(const stream_profile& a,
139  const stream_profile& b)
140  {
141  return (a.width == b.width) &&
142  (a.height == b.height) &&
143  (a.fps == b.fps) &&
144  (a.format == b.format);
145  }
146 
147 #pragma pack(push, 1)
148  struct uvc_header
149  {
150  uint8_t length; // UVC Metadata total length is
151  // limited by design to 255 bytes
154  uint8_t source_clock[6];
155  };
156 
157  struct hid_header
158  {
159  uint8_t length; // HID report total size. Limited to 255
160  uint8_t report_type; // Curently supported: IMU/Custom Temperature
161  uint64_t timestamp; // Driver-produced/FW-based timestamp. Note that currently only the lower 32bit are used
162  };
163 #pragma pack(pop)
164 
165  constexpr uint8_t uvc_header_size = sizeof(uvc_header);
166  constexpr uint8_t hid_header_size = sizeof(hid_header);
167 
169  {
170  size_t frame_size;
172  const void * pixels;
173  const void * metadata;
175  };
176 
177  typedef std::function<void(stream_profile, frame_object, std::function<void()>)> frame_callback;
178 
180  {
181  std::string id = ""; // to distinguish between different pins of the same device
182  uint16_t vid = 0;
183  uint16_t pid = 0;
184  uint16_t mi = 0;
186  std::string device_path = "";
187  std::string serial = "";
188  usb_spec conn_spec = usb_undefined;
189  uint32_t uvc_capabilities = 0;
190  bool has_metadata_node = false;
191  std::string metadata_node_id = "";
192 
193  operator std::string()
194  {
195  std::stringstream s;
196  s << "id- " << id <<
197  "\nvid- " << std::hex << vid <<
198  "\npid- " << std::hex << pid <<
199  "\nmi- " << mi <<
200  "\nunique_id- " << unique_id <<
201  "\npath- " << device_path <<
202  "\nsusb specification- " << std::hex << (uint16_t)conn_spec << std::dec <<
203  (has_metadata_node ? ( "\nmetadata node-" + metadata_node_id) : "");
204 
205  return s.str();
206  }
207 
208  bool operator <(const uvc_device_info& obj) const
209  {
210  return (std::make_tuple(id, vid, pid, mi, unique_id, device_path) < std::make_tuple(obj.id, obj.vid, obj.pid, obj.mi, obj.unique_id, obj.device_path));
211  }
212 
213  };
214 
215  inline bool operator==(const uvc_device_info& a,
216  const uvc_device_info& b)
217  {
218  return (a.vid == b.vid) &&
219  (a.pid == b.pid) &&
220  (a.mi == b.mi) &&
221  (a.unique_id == b.unique_id) &&
222  (a.id == b.id) &&
223  (a.device_path == b.device_path) &&
224  (a.conn_spec == b.conn_spec);
225  }
226 
227  inline bool operator==(const usb_device_info& a,
228  const usb_device_info& b)
229  {
230  return (a.id == b.id) &&
231  (a.vid == b.vid) &&
232  (a.pid == b.pid) &&
233  (a.mi == b.mi) &&
234  (a.unique_id == b.unique_id) &&
235  (a.conn_spec == b.conn_spec);
236  }
237 
238 
239 
241  {
243 
244  operator std::string()
245  {
246  return file_path;
247  }
248  };
249 
250  inline bool operator==(const playback_device_info& a,
251  const playback_device_info& b)
252  {
253  return (a.file_path == b.file_path);
254  }
255 
257  {
258  void* device_ptr;
259 
260  operator std::string() const
261  {
262  std::ostringstream oss;
263  oss << device_ptr;
264  return oss.str();
265  }
266  };
267 
268  inline bool operator==(const tm2_device_info& a,
269  const tm2_device_info& b)
270  {
271  return (a.device_ptr == b.device_ptr);
272  }
273 
274  struct hid_sensor
275  {
277  };
278 
280  {
283  };
284 
289  };
290 
291  struct sensor_data
292  {
295  };
296 
297  struct hid_profile
298  {
301  };
302 
311  };
312 
313 #pragma pack(push, 1)
315  {
316  short x;
317  char reserved1[2];
318  short y;
319  char reserved2[2];
320  short z;
321  char reserved3[2];
324  };
325 #pragma pack(pop)
326 
327  typedef std::function<void(const sensor_data&)> hid_callback;
328 
330  {
331  public:
332  virtual ~hid_device() = default;
333  virtual void register_profiles(const std::vector<hid_profile>& hid_profiles) = 0;// TODO: this should be queried from the device
334  virtual void open(const std::vector<hid_profile>& hid_profiles) = 0;
335  virtual void close() = 0;
336  virtual void stop_capture() = 0;
337  virtual void start_capture(hid_callback callback) = 0;
338  virtual std::vector<hid_sensor> get_sensors() = 0;
339  virtual std::vector<uint8_t> get_custom_report_data(const std::string& custom_sensor_name,
340  const std::string& report_name,
341  custom_sensor_report_field report_field) = 0;
342  };
343 
344  struct request_mapping;
345 
347  {
348  public:
349  virtual void probe_and_commit(stream_profile profile, frame_callback callback, int buffers = DEFAULT_V4L2_FRAME_BUFFERS) = 0;
350  virtual void stream_on(std::function<void(const notification& n)> error_handler = [](const notification& n){}) = 0;
351  virtual void start_callbacks() = 0;
352  virtual void stop_callbacks() = 0;
353  virtual void close(stream_profile profile) = 0;
354 
355  virtual void set_power_state(power_state state) = 0;
356  virtual power_state get_power_state() const = 0;
357 
358  virtual void init_xu(const extension_unit& xu) = 0;
359  virtual bool set_xu(const extension_unit& xu, uint8_t ctrl, const uint8_t* data, int len) = 0;
360  virtual bool get_xu(const extension_unit& xu, uint8_t ctrl, uint8_t* data, int len) const = 0;
361  virtual control_range get_xu_range(const extension_unit& xu, uint8_t ctrl, int len) const = 0;
362 
363  virtual bool get_pu(rs2_option opt, int32_t& value) const = 0;
364  virtual bool set_pu(rs2_option opt, int32_t value) = 0;
365  virtual control_range get_pu_range(rs2_option opt) const = 0;
366 
367  virtual std::vector<stream_profile> get_profiles() const = 0;
368 
369  virtual void lock() const = 0;
370  virtual void unlock() const = 0;
371 
372  virtual std::string get_device_location() const = 0;
373  virtual usb_spec get_usb_specification() const = 0;
374 
375  virtual ~uvc_device() = default;
376 
377  protected:
378  std::function<void(const notification& n)> _error_handler;
379  };
380 
382  {
383  public:
384  explicit retry_controls_work_around(std::shared_ptr<uvc_device> dev)
385  : _dev(dev) {}
386 
388  {
389  _dev->probe_and_commit(profile, callback, buffers);
390  }
391 
392  void stream_on(std::function<void(const notification& n)> error_handler = [](const notification& n){}) override
393  {
394  _dev->stream_on(error_handler);
395  }
396 
397  void start_callbacks() override
398  {
399  _dev->start_callbacks();
400  }
401 
402  void stop_callbacks() override
403  {
404  _dev->stop_callbacks();
405  }
406 
407  void close(stream_profile profile) override
408  {
409  _dev->close(profile);
410  }
411 
413  {
414  _dev->set_power_state(state);
415  }
416 
417  power_state get_power_state() const override
418  {
419  return _dev->get_power_state();
420  }
421 
422  void init_xu(const extension_unit& xu) override
423  {
424  _dev->init_xu(xu);
425  }
426 
427  bool set_xu(const extension_unit& xu, uint8_t ctrl, const uint8_t* data, int len) override
428  {
429  for (auto i = 0; i < MAX_RETRIES; ++i)
430  {
431  if (_dev->set_xu(xu, ctrl, data, len))
432  return true;
433 
434  std::this_thread::sleep_for(std::chrono::milliseconds(DELAY_FOR_RETRIES));
435  }
436  return false;
437  }
438 
439  bool get_xu(const extension_unit& xu, uint8_t ctrl, uint8_t* data, int len) const override
440  {
441  for (auto i = 0; i < MAX_RETRIES; ++i)
442  {
443  if (_dev->get_xu(xu, ctrl, data, len))
444  return true;
445 
446  std::this_thread::sleep_for(std::chrono::milliseconds(DELAY_FOR_RETRIES));
447  }
448  return false;
449  }
450 
451  control_range get_xu_range(const extension_unit& xu, uint8_t ctrl, int len) const override
452  {
453  return _dev->get_xu_range(xu, ctrl, len);
454  }
455 
456  bool get_pu(rs2_option opt, int32_t& value) const override
457  {
458  for (auto i = 0; i < MAX_RETRIES; ++i)
459  {
460  if (_dev->get_pu(opt, value))
461  return true;
462 
463  std::this_thread::sleep_for(std::chrono::milliseconds(DELAY_FOR_RETRIES));
464  }
465  return false;
466  }
467 
468  bool set_pu(rs2_option opt, int32_t value) override
469  {
470  for (auto i = 0; i < MAX_RETRIES; ++i)
471  {
472  if (_dev->set_pu(opt, value))
473  return true;
474 
475  std::this_thread::sleep_for(std::chrono::milliseconds(DELAY_FOR_RETRIES));
476  }
477  return false;
478  }
479 
481  {
482  return _dev->get_pu_range(opt);
483  }
484 
485  std::vector<stream_profile> get_profiles() const override
486  {
487  return _dev->get_profiles();
488  }
489 
491  {
492  return _dev->get_device_location();
493  }
494 
496  {
497  return _dev->get_usb_specification();
498  }
499 
500  void lock() const override { _dev->lock(); }
501  void unlock() const override { _dev->unlock(); }
502 
503  private:
504  std::shared_ptr<uvc_device> _dev;
505  };
506 
507 
508  class device_watcher;
509 
511  {
513 
514  backend_device_group(const std::vector<uvc_device_info>& uvc_devices, const std::vector<usb_device_info>& usb_devices, const std::vector<hid_device_info>& hid_devices)
515  :uvc_devices(uvc_devices), usb_devices(usb_devices), hid_devices(hid_devices) {}
516 
517  backend_device_group(const std::vector<usb_device_info>& usb_devices)
518  :usb_devices(usb_devices) {}
519 
520  backend_device_group(const std::vector<uvc_device_info>& uvc_devices, const std::vector<usb_device_info>& usb_devices)
521  :uvc_devices(uvc_devices), usb_devices(usb_devices) {}
522 
523  backend_device_group(const std::vector<playback_device_info>& playback_devices) : playback_devices(playback_devices) {}
524 
525  std::vector<uvc_device_info> uvc_devices;
526  std::vector<usb_device_info> usb_devices;
527  std::vector<hid_device_info> hid_devices;
528  std::vector<playback_device_info> playback_devices;
529 
531  {
532  return !list_changed(uvc_devices, other.uvc_devices) &&
533  !list_changed(hid_devices, other.hid_devices) &&
534  !list_changed(playback_devices, other.playback_devices);
535  }
536 
537  operator std::string()
538  {
539  std::string s;
540  s = uvc_devices.size()>0 ? "uvc devices:\n" : "";
541  for (auto uvc : uvc_devices)
542  {
543  s += uvc;
544  s += "\n\n";
545  }
546 
547  s += usb_devices.size()>0 ? "usb devices:\n" : "";
548  for (auto usb : usb_devices)
549  {
550  s += usb;
551  s += "\n\n";
552  }
553 
554  s += hid_devices.size()>0 ? "hid devices: \n" : "";
555  for (auto hid : hid_devices)
556  {
557  s += hid;
558  s += "\n\n";
559  }
560 
561  s += playback_devices.size()>0 ? "playback devices: \n" : "";
562  for (auto playback_device : playback_devices)
563  {
564  s += playback_device;
565  s += "\n\n";
566  }
567 
568  return s;
569  }
570  };
571 
572 
573 
574  typedef std::function<void(backend_device_group old, backend_device_group curr)> device_changed_callback;
575 
576  class backend
577  {
578  public:
579  virtual std::shared_ptr<uvc_device> create_uvc_device(uvc_device_info info) const = 0;
580  virtual std::vector<uvc_device_info> query_uvc_devices() const = 0;
581 
582  virtual std::shared_ptr<command_transfer> create_usb_device(usb_device_info info) const = 0;
583  virtual std::vector<usb_device_info> query_usb_devices() const = 0;
584 
585  virtual std::shared_ptr<hid_device> create_hid_device(hid_device_info info) const = 0;
586  virtual std::vector<hid_device_info> query_hid_devices() const = 0;
587 
588  virtual std::shared_ptr<time_service> create_time_service() const = 0;
589 
590  virtual std::shared_ptr<device_watcher> create_device_watcher() const = 0;
591 
592  virtual std::string get_device_serial(uint16_t device_vid, uint16_t device_pid, const std::string& device_uid) const
593  {
594  std::string empty_str;
595  return empty_str;
596  }
597 
598  virtual ~backend() = default;
599  };
600 
602  {
603  public:
604  void register_profiles(const std::vector<hid_profile>& hid_profiles) override { _hid_profiles = hid_profiles; }
605  void open(const std::vector<hid_profile>& sensor_iio) override
606  {
607  for (auto&& dev : _dev) dev->open(sensor_iio);
608  }
609 
610  void close() override
611  {
612  for (auto&& dev : _dev) dev->close();
613  }
614 
615  void stop_capture() override
616  {
617  _dev.front()->stop_capture();
618  }
619 
620  void start_capture(hid_callback callback) override
621  {
622  _dev.front()->start_capture(callback);
623  }
624 
625  std::vector<hid_sensor> get_sensors() override
626  {
627  return _dev.front()->get_sensors();
628  }
629 
630  explicit multi_pins_hid_device(const std::vector<std::shared_ptr<hid_device>>& dev)
631  : _dev(dev)
632  {
633  }
634 
635  std::vector<uint8_t> get_custom_report_data(const std::string& custom_sensor_name,
636  const std::string& report_name,
637  custom_sensor_report_field report_field) override
638  {
639  return _dev.front()->get_custom_report_data(custom_sensor_name, report_name, report_field);
640  }
641 
642  private:
643  std::vector<std::shared_ptr<hid_device>> _dev;
644  std::vector<hid_profile> _hid_profiles;
645  };
646 
648  {
649  public:
650  explicit multi_pins_uvc_device(const std::vector<std::shared_ptr<uvc_device>>& dev)
651  : _dev(dev)
652  {}
653 
655  {
656  auto dev_index = get_dev_index_by_profiles(profile);
657  _configured_indexes.insert(dev_index);
658  _dev[dev_index]->probe_and_commit(profile, callback, buffers);
659  }
660 
661 
662  void stream_on(std::function<void(const notification& n)> error_handler = [](const notification& n){}) override
663  {
664  for (auto& elem : _configured_indexes)
665  {
666  _dev[elem]->stream_on(error_handler);
667  }
668  }
669  void start_callbacks() override
670  {
671  for (auto& elem : _configured_indexes)
672  {
673  _dev[elem]->start_callbacks();
674  }
675  }
676 
677  void stop_callbacks() override
678  {
679  for (auto& elem : _configured_indexes)
680  {
681  _dev[elem]->stop_callbacks();
682  }
683  }
684 
685  void close(stream_profile profile) override
686  {
687  auto dev_index = get_dev_index_by_profiles(profile);
688  _dev[dev_index]->close(profile);
689  _configured_indexes.erase(dev_index);
690  }
691 
693  {
694  for (auto& elem : _dev)
695  {
696  elem->set_power_state(state);
697  }
698  }
699 
700  power_state get_power_state() const override
701  {
702  return _dev.front()->get_power_state();
703  }
704 
705  void init_xu(const extension_unit& xu) override
706  {
707  _dev.front()->init_xu(xu);
708  }
709 
710  bool set_xu(const extension_unit& xu, uint8_t ctrl, const uint8_t* data, int len) override
711  {
712  return _dev.front()->set_xu(xu, ctrl, data, len);
713  }
714 
715  bool get_xu(const extension_unit& xu, uint8_t ctrl, uint8_t* data, int len) const override
716  {
717  return _dev.front()->get_xu(xu, ctrl, data, len);
718  }
719 
720  control_range get_xu_range(const extension_unit& xu, uint8_t ctrl, int len) const override
721  {
722  return _dev.front()->get_xu_range(xu, ctrl, len);
723  }
724 
725  bool get_pu(rs2_option opt, int32_t& value) const override
726  {
727  return _dev.front()->get_pu(opt, value);
728  }
729 
730  bool set_pu(rs2_option opt, int32_t value) override
731  {
732  return _dev.front()->set_pu(opt, value);
733  }
734 
736  {
737  return _dev.front()->get_pu_range(opt);
738  }
739 
740  std::vector<stream_profile> get_profiles() const override
741  {
742  std::vector<stream_profile> all_stream_profiles;
743  for (auto& elem : _dev)
744  {
745  auto pin_stream_profiles = elem->get_profiles();
746  all_stream_profiles.insert(all_stream_profiles.end(),
747  pin_stream_profiles.begin(), pin_stream_profiles.end());
748  }
749  return all_stream_profiles;
750  }
751 
753  {
754  return _dev.front()->get_device_location();
755  }
756 
758  {
759  return _dev.front()->get_usb_specification();
760  }
761 
762  void lock() const override
763  {
764  std::vector<uvc_device*> locked_dev;
765  try {
766  for (auto& elem : _dev)
767  {
768  elem->lock();
769  locked_dev.push_back(elem.get());
770  }
771  }
772  catch(...)
773  {
774  for (auto& elem : locked_dev)
775  {
776  elem->unlock();
777  }
778  throw;
779  }
780  }
781 
782  void unlock() const override
783  {
784  for (auto& elem : _dev)
785  {
786  elem->unlock();
787  }
788  }
789 
790  private:
792  {
793  uint32_t dev_index = 0;
794  for (auto& elem : _dev)
795  {
796  auto pin_stream_profiles = elem->get_profiles();
797  auto it = find(pin_stream_profiles.begin(), pin_stream_profiles.end(), profile);
798  if (it != pin_stream_profiles.end())
799  {
800  return dev_index;
801  }
802  ++dev_index;
803  }
804  throw std::runtime_error("profile not found");
805  }
806 
807  std::vector<std::shared_ptr<uvc_device>> _dev;
808  std::set<uint32_t> _configured_indexes;
809  };
810 
811  std::shared_ptr<backend> create_backend();
812 
813 
814 
816  {
817  public:
818  virtual void start(device_changed_callback callback) = 0;
819  virtual void stop() = 0;
820  virtual ~device_watcher() {};
821  };
822  }
823 
824  double monotonic_to_realtime(double monotonic);
825 }
826 
827 #endif
static const textual_icon lock
Definition: model-views.h:218
std::vector< std::shared_ptr< uvc_device > > _dev
Definition: backend.h:807
GLboolean GLboolean GLboolean b
static const textual_icon unlock
Definition: model-views.h:237
bool set_xu(const extension_unit &xu, uint8_t ctrl, const uint8_t *data, int len) override
Definition: backend.h:710
std::string get_device_location() const override
Definition: backend.h:752
bool list_changed(const std::vector< T > &list1, const std::vector< T > &list2, std::function< bool(T, T)> equal=[](T first, T second){return first==second;})
Definition: backend.h:42
std::vector< uint8_t > max
Definition: backend.h:88
std::vector< hid_sensor > get_sensors() override
Definition: backend.h:625
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
Definition: rs_option.h:22
GLdouble s
void close(stream_profile profile) override
Definition: backend.h:407
virtual std::string get_device_serial(uint16_t device_vid, uint16_t device_pid, const std::string &device_uid) const
Definition: backend.h:592
std::vector< playback_device_info > playback_devices
Definition: backend.h:528
constexpr uint8_t uvc_header_size
Definition: backend.h:165
usb_spec get_usb_specification() const override
Definition: backend.h:757
GLfloat value
void init_xu(const extension_unit &xu) override
Definition: backend.h:422
const uint8_t MAX_META_DATA_SIZE
Definition: backend.h:34
backend_device_group(const std::vector< uvc_device_info > &uvc_devices, const std::vector< usb_device_info > &usb_devices)
Definition: backend.h:520
backend_device_group(const std::vector< playback_device_info > &playback_devices)
Definition: backend.h:523
unsigned short uint16_t
Definition: stdint.h:79
retry_controls_work_around(std::shared_ptr< uvc_device > dev)
Definition: backend.h:384
GLsizei const GLchar *const * string
control_range get_xu_range(const extension_unit &xu, uint8_t ctrl, int len) const override
Definition: backend.h:720
GLdouble n
Definition: glext.h:1966
unsigned char uint8_t
Definition: stdint.h:78
GLhandleARB obj
Definition: glext.h:4157
void set_power_state(power_state state) override
Definition: backend.h:412
static const textual_icon stop
Definition: model-views.h:225
std::vector< uint8_t > get_custom_report_data(const std::string &custom_sensor_name, const std::string &report_name, custom_sensor_report_field report_field) override
Definition: backend.h:635
bool get_xu(const extension_unit &xu, uint8_t ctrl, uint8_t *data, int len) const override
Definition: backend.h:439
std::shared_ptr< backend > create_backend()
GLenum GLuint id
GLboolean GLboolean GLboolean GLboolean a
GLenum GLsizei len
Definition: glext.h:3285
def info(name, value, persistent=False)
Definition: test.py:301
const uint16_t MAX_RETRIES
Definition: backend.h:30
bool get_xu(const extension_unit &xu, uint8_t ctrl, uint8_t *data, int len) const override
Definition: backend.h:715
bool set_xu(const extension_unit &xu, uint8_t ctrl, const uint8_t *data, int len) override
Definition: backend.h:427
std::vector< hid_device_info > hid_devices
Definition: backend.h:527
multi_pins_uvc_device(const std::vector< std::shared_ptr< uvc_device >> &dev)
Definition: backend.h:650
void probe_and_commit(stream_profile profile, frame_callback callback, int buffers) override
Definition: backend.h:387
bool get_pu(rs2_option opt, int32_t &value) const override
Definition: backend.h:456
control_range(std::vector< uint8_t > in_min, std::vector< uint8_t > in_max, std::vector< uint8_t > in_step, std::vector< uint8_t > in_def)
Definition: backend.h:83
const uint16_t DELAY_FOR_RETRIES
Definition: backend.h:32
std::function< void(backend_device_group old, backend_device_group curr)> device_changed_callback
Definition: backend.h:574
unsigned int uint32_t
Definition: stdint.h:80
bool operator<(const stream_profile &lhs, const stream_profile &rhs)
Definition: src/types.h:694
void init_xu(const extension_unit &xu) override
Definition: backend.h:705
control_range get_xu_range(const extension_unit &xu, uint8_t ctrl, int len) const override
Definition: backend.h:451
std::vector< hid_profile > _hid_profiles
Definition: backend.h:644
void register_profiles(const std::vector< hid_profile > &hid_profiles) override
Definition: backend.h:604
void stream_on(std::function< void(const notification &n)> error_handler=[](const notification &n){}) override
Definition: backend.h:392
void probe_and_commit(stream_profile profile, frame_callback callback, int buffers) override
Definition: backend.h:654
def find(dir, mask)
Definition: file.py:25
def callback(frame)
Definition: t265_stereo.py:91
unsigned __int64 uint64_t
Definition: stdint.h:90
GLuint start
std::vector< std::shared_ptr< hid_device > > _dev
Definition: backend.h:643
void close(stream_profile profile) override
Definition: backend.h:685
GLint first
std::tuple< uint32_t, uint32_t, uint32_t, uint32_t > stream_profile_tuple
Definition: backend.h:122
void set_power_state(power_state state) override
Definition: backend.h:692
const GLuint * buffers
std::string get_device_location() const override
Definition: backend.h:490
std::vector< stream_profile > get_profiles() const override
Definition: backend.h:485
bool set_pu(rs2_option opt, int32_t value) override
Definition: backend.h:730
uint32_t get_dev_index_by_profiles(const stream_profile &profile) const
Definition: backend.h:791
void start_capture(hid_callback callback) override
Definition: backend.h:620
std::function< void(const notification &n)> _error_handler
Definition: backend.h:378
bool get_pu(rs2_option opt, int32_t &value) const override
Definition: backend.h:725
control_range(int32_t in_min, int32_t in_max, int32_t in_step, int32_t in_def)
Definition: backend.h:76
std::function< void(stream_profile, frame_object, std::function< void()>)> frame_callback
Definition: backend.h:177
double monotonic_to_realtime(double monotonic)
Definition: backend.cpp:26
void stream_on(std::function< void(const notification &n)> error_handler=[](const notification &n){}) override
Definition: backend.h:662
rs2_time_t get_time() const override
Definition: backend.h:106
static auto it
std::vector< usb_device_info > usb_devices
Definition: backend.h:526
multi_pins_hid_device(const std::vector< std::shared_ptr< hid_device >> &dev)
Definition: backend.h:630
GLint GLsizei count
std::vector< uint8_t > def
Definition: backend.h:90
std::shared_ptr< uvc_device > _dev
Definition: backend.h:504
std::vector< uint8_t > min
Definition: backend.h:87
int i
void populate_raw_data(std::vector< uint8_t > &vec, int32_t value)
Definition: backend.cpp:19
backend_device_group(const std::vector< usb_device_info > &usb_devices)
Definition: backend.h:517
control_range get_pu_range(rs2_option opt) const override
Definition: backend.h:735
power_state get_power_state() const override
Definition: backend.h:417
signed int int32_t
Definition: stdint.h:77
std::function< void(const sensor_data &)> hid_callback
Definition: backend.h:327
std::vector< uvc_device_info > uvc_devices
Definition: backend.h:525
power_state get_power_state() const override
Definition: backend.h:700
bool operator==(const stream_profile &a, const stream_profile &b)
Definition: backend.h:138
const uint8_t DEFAULT_V4L2_FRAME_BUFFERS
Definition: backend.h:31
std::vector< uint8_t > step
Definition: backend.h:89
usb_spec get_usb_specification() const override
Definition: backend.h:495
backend_device_group(const std::vector< uvc_device_info > &uvc_devices, const std::vector< usb_device_info > &usb_devices, const std::vector< hid_device_info > &hid_devices)
Definition: backend.h:514
std::vector< stream_profile > get_profiles() const override
Definition: backend.h:740
double rs2_time_t
Definition: rs_types.h:300
constexpr uint8_t hid_header_size
Definition: backend.h:166
void open(const std::vector< hid_profile > &sensor_iio) override
Definition: backend.h:605
bool set_pu(rs2_option opt, int32_t value) override
Definition: backend.h:468
control_range get_pu_range(rs2_option opt) const override
Definition: backend.h:480
double get_time()
Definition: rs_internal.hpp:62
Definition: parser.hpp:150


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