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 
6 #include <librealsense2/h/rs_types.h> // Inherit all type definitions in the public API
8 #include "usb/usb-types.h"
9 #include "usb/usb-device.h"
10 #include "hid/hid-types.h"
11 #include "command_transfer.h"
12 
13 #include <memory> // For shared_ptr
14 #include <functional> // For function
15 #include <thread> // For this_thread::sleep_for
16 #include <vector>
17 #include <algorithm>
18 #include <set>
19 #include <iterator>
20 #include <tuple>
21 #include <map>
22 #include <cstring>
23 #include <string>
24 #include <sstream>
25 #include <fstream>
26 
27 
28 const uint16_t MAX_RETRIES = 100;
31 const int DISCONNECT_PERIOD_MS = 6000;
32 const int POLLING_DEVICES_INTERVAL_MS = 2000;
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 
158  {
161  };
162 
163  struct hid_header
164  {
165  uint8_t length; // HID report total size. Limited to 255
166  uint8_t report_type; // Curently supported: IMU/Custom Temperature
167  uint64_t timestamp; // Driver-produced/FW-based timestamp. Note that currently only the lower 32bit are used
168  };
169 #pragma pack(pop)
170 
171  constexpr uint8_t uvc_header_size = sizeof(uvc_header);
172  constexpr uint8_t hid_header_size = sizeof(hid_header);
174 
176  {
177  size_t frame_size;
179  const void * pixels;
180  const void * metadata;
182  };
183 
184  typedef std::function<void(stream_profile, frame_object, std::function<void()>)> frame_callback;
185 
187  {
188  std::string id = ""; // to distinguish between different pins of the same device
189  uint16_t vid = 0;
191  uint16_t mi = 0;
192  std::string unique_id = "";
193  std::string device_path = "";
194  std::string serial = "";
195  usb_spec conn_spec = usb_undefined;
196  uint32_t uvc_capabilities = 0;
197  bool has_metadata_node = false;
198  std::string metadata_node_id = "";
199 
200  operator std::string()
201  {
202  std::stringstream s;
203  s << "id- " << id <<
204  "\nvid- " << std::hex << vid <<
205  "\npid- " << std::hex << pid <<
206  "\nmi- " << std::dec << mi <<
207  "\nunique_id- " << unique_id <<
208  "\npath- " << device_path <<
209  "\nUVC capabilities- " << std::hex << uvc_capabilities <<
210  "\nUVC specification- " << std::hex << (uint16_t)conn_spec << std::dec <<
211  (has_metadata_node ? ( "\nmetadata node-" + metadata_node_id) : "") << std::endl;
212 
213  return s.str();
214  }
215 
216  bool operator <(const uvc_device_info& obj) const
217  {
218  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));
219  }
220 
221  };
222 
223  inline bool operator==(const uvc_device_info& a,
224  const uvc_device_info& b)
225  {
226  return (a.vid == b.vid) &&
227  (a.pid == b.pid) &&
228  (a.mi == b.mi) &&
229  (a.unique_id == b.unique_id) &&
230  (a.id == b.id) &&
231  (a.device_path == b.device_path) &&
232  (a.conn_spec == b.conn_spec);
233  }
234 
235  inline bool operator==(const usb_device_info& a,
236  const usb_device_info& b)
237  {
238  return (a.id == b.id) &&
239  (a.vid == b.vid) &&
240  (a.pid == b.pid) &&
241  (a.mi == b.mi) &&
242  (a.unique_id == b.unique_id) &&
243  (a.conn_spec == b.conn_spec);
244  }
245 
246 
247 
249  {
250  std::string file_path;
251 
252  operator std::string()
253  {
254  return file_path;
255  }
256  };
257 
258  inline bool operator==(const playback_device_info& a,
259  const playback_device_info& b)
260  {
261  return (a.file_path == b.file_path);
262  }
263 
265  {
266  void* device_ptr;
267 
268  operator std::string() const
269  {
270  std::ostringstream oss;
271  oss << device_ptr;
272  return oss.str();
273  }
274  };
275 
276  inline bool operator==(const tm2_device_info& a,
277  const tm2_device_info& b)
278  {
279  return (a.device_ptr == b.device_ptr);
280  }
281 
282  struct hid_sensor
283  {
284  std::string name;
285  };
286 
288  {
290  std::string name;
291  };
292 
297  };
298 
299  struct sensor_data
300  {
303  };
304 
305  struct hid_profile
306  {
307  std::string sensor_name;
309  };
310 
319  };
320 
321 #pragma pack(push, 1)
323  {
324  short x;
325  char reserved1[2];
326  short y;
327  char reserved2[2];
328  short z;
329  char reserved3[2];
332  };
333 #pragma pack(pop)
334 
335  typedef std::function<void(const sensor_data&)> hid_callback;
336 
338  {
339  public:
340  virtual ~hid_device() = default;
341  virtual void register_profiles(const std::vector<hid_profile>& hid_profiles) = 0;// TODO: this should be queried from the device
342  virtual void open(const std::vector<hid_profile>& hid_profiles) = 0;
343  virtual void close() = 0;
344  virtual void stop_capture() = 0;
345  virtual void start_capture(hid_callback callback) = 0;
346  virtual std::vector<hid_sensor> get_sensors() = 0;
347  virtual std::vector<uint8_t> get_custom_report_data(const std::string& custom_sensor_name,
348  const std::string& report_name,
349  custom_sensor_report_field report_field) = 0;
350  };
351 
352  struct request_mapping;
353 
355  {
356  public:
357  virtual void probe_and_commit(stream_profile profile, frame_callback callback, int buffers = DEFAULT_V4L2_FRAME_BUFFERS) = 0;
358  virtual void stream_on(std::function<void(const notification& n)> error_handler = [](const notification& n){}) = 0;
359  virtual void start_callbacks() = 0;
360  virtual void stop_callbacks() = 0;
361  virtual void close(stream_profile profile) = 0;
362 
363  virtual void set_power_state(power_state state) = 0;
364  virtual power_state get_power_state() const = 0;
365 
366  virtual void init_xu(const extension_unit& xu) = 0;
367  virtual bool set_xu(const extension_unit& xu, uint8_t ctrl, const uint8_t* data, int len) = 0;
368  virtual bool get_xu(const extension_unit& xu, uint8_t ctrl, uint8_t* data, int len) const = 0;
369  virtual control_range get_xu_range(const extension_unit& xu, uint8_t ctrl, int len) const = 0;
370 
371  virtual bool get_pu(rs2_option opt, int32_t& value) const = 0;
372  virtual bool set_pu(rs2_option opt, int32_t value) = 0;
373  virtual control_range get_pu_range(rs2_option opt) const = 0;
374 
375  virtual std::vector<stream_profile> get_profiles() const = 0;
376 
377  virtual void lock() const = 0;
378  virtual void unlock() const = 0;
379 
380  virtual std::string get_device_location() const = 0;
381  virtual usb_spec get_usb_specification() const = 0;
382 
383  virtual ~uvc_device() = default;
384 
385  protected:
386  std::function<void(const notification& n)> _error_handler;
387  };
388 
390  {
391  public:
392  explicit retry_controls_work_around(std::shared_ptr<uvc_device> dev)
393  : _dev(dev) {}
394 
396  {
397  _dev->probe_and_commit(profile, callback, buffers);
398  }
399 
400  void stream_on(std::function<void(const notification& n)> error_handler = [](const notification& n){}) override
401  {
402  _dev->stream_on(error_handler);
403  }
404 
405  void start_callbacks() override
406  {
407  _dev->start_callbacks();
408  }
409 
410  void stop_callbacks() override
411  {
412  _dev->stop_callbacks();
413  }
414 
415  void close(stream_profile profile) override
416  {
417  _dev->close(profile);
418  }
419 
421  {
422  _dev->set_power_state(state);
423  }
424 
425  power_state get_power_state() const override
426  {
427  return _dev->get_power_state();
428  }
429 
430  void init_xu(const extension_unit& xu) override
431  {
432  _dev->init_xu(xu);
433  }
434 
435  bool set_xu(const extension_unit& xu, uint8_t ctrl, const uint8_t* data, int len) override
436  {
437  for (auto i = 0; i < MAX_RETRIES; ++i)
438  {
439  if (_dev->set_xu(xu, ctrl, data, len))
440  return true;
441 
442  std::this_thread::sleep_for(std::chrono::milliseconds(DELAY_FOR_RETRIES));
443  }
444  return false;
445  }
446 
447  bool get_xu(const extension_unit& xu, uint8_t ctrl, uint8_t* data, int len) const override
448  {
449  for (auto i = 0; i < MAX_RETRIES; ++i)
450  {
451  if (_dev->get_xu(xu, ctrl, data, len))
452  return true;
453 
454  std::this_thread::sleep_for(std::chrono::milliseconds(DELAY_FOR_RETRIES));
455  }
456  return false;
457  }
458 
459  control_range get_xu_range(const extension_unit& xu, uint8_t ctrl, int len) const override
460  {
461  return _dev->get_xu_range(xu, ctrl, len);
462  }
463 
464  bool get_pu(rs2_option opt, int32_t& value) const override
465  {
466  for (auto i = 0; i < MAX_RETRIES; ++i)
467  {
468  if (_dev->get_pu(opt, value))
469  return true;
470 
471  std::this_thread::sleep_for(std::chrono::milliseconds(DELAY_FOR_RETRIES));
472  }
473  return false;
474  }
475 
476  bool set_pu(rs2_option opt, int32_t value) override
477  {
478  for (auto i = 0; i < MAX_RETRIES; ++i)
479  {
480  if (_dev->set_pu(opt, value))
481  return true;
482 
483  std::this_thread::sleep_for(std::chrono::milliseconds(DELAY_FOR_RETRIES));
484  }
485  return false;
486  }
487 
489  {
490  return _dev->get_pu_range(opt);
491  }
492 
493  std::vector<stream_profile> get_profiles() const override
494  {
495  return _dev->get_profiles();
496  }
497 
498  std::string get_device_location() const override
499  {
500  return _dev->get_device_location();
501  }
502 
504  {
505  return _dev->get_usb_specification();
506  }
507 
508  void lock() const override { _dev->lock(); }
509  void unlock() const override { _dev->unlock(); }
510 
511  private:
512  std::shared_ptr<uvc_device> _dev;
513  };
514 
515 
516  class device_watcher;
517 
519  {
521 
522  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)
523  :uvc_devices(uvc_devices), usb_devices(usb_devices), hid_devices(hid_devices) {}
524 
525  backend_device_group(const std::vector<usb_device_info>& usb_devices)
526  :usb_devices(usb_devices) {}
527 
528  backend_device_group(const std::vector<uvc_device_info>& uvc_devices, const std::vector<usb_device_info>& usb_devices)
529  :uvc_devices(uvc_devices), usb_devices(usb_devices) {}
530 
531  backend_device_group(const std::vector<playback_device_info>& playback_devices) : playback_devices(playback_devices) {}
532 
533  std::vector<uvc_device_info> uvc_devices;
534  std::vector<usb_device_info> usb_devices;
535  std::vector<hid_device_info> hid_devices;
536  std::vector<playback_device_info> playback_devices;
537 
539  {
540  return !list_changed(uvc_devices, other.uvc_devices) &&
541  !list_changed(hid_devices, other.hid_devices) &&
542  !list_changed(playback_devices, other.playback_devices);
543  }
544 
545  operator std::string()
546  {
547  std::string s;
548  s = uvc_devices.size()>0 ? "uvc devices:\n" : "";
549  for (auto uvc : uvc_devices)
550  {
551  s += uvc;
552  s += "\n\n";
553  }
554 
555  s += usb_devices.size()>0 ? "usb devices:\n" : "";
556  for (auto usb : usb_devices)
557  {
558  s += usb;
559  s += "\n\n";
560  }
561 
562  s += hid_devices.size()>0 ? "hid devices: \n" : "";
563  for (auto hid : hid_devices)
564  {
565  s += hid;
566  s += "\n\n";
567  }
568 
569  s += playback_devices.size()>0 ? "playback devices: \n" : "";
570  for (auto playback_device : playback_devices)
571  {
572  s += playback_device;
573  s += "\n\n";
574  }
575 
576  return s;
577  }
578  };
579 
580 
581 
582  typedef std::function<void(backend_device_group old, backend_device_group curr)> device_changed_callback;
583 
584  class backend
585  {
586  public:
587  virtual std::shared_ptr<uvc_device> create_uvc_device(uvc_device_info info) const = 0;
588  virtual std::vector<uvc_device_info> query_uvc_devices() const = 0;
589 
590  virtual std::shared_ptr<command_transfer> create_usb_device(usb_device_info info) const = 0;
591  virtual std::vector<usb_device_info> query_usb_devices() const = 0;
592 
593  virtual std::shared_ptr<hid_device> create_hid_device(hid_device_info info) const = 0;
594  virtual std::vector<hid_device_info> query_hid_devices() const = 0;
595 
596  virtual std::shared_ptr<time_service> create_time_service() const = 0;
597 
598  virtual std::shared_ptr<device_watcher> create_device_watcher() const = 0;
599 
600  virtual std::string get_device_serial(uint16_t device_vid, uint16_t device_pid, const std::string& device_uid) const
601  {
602  std::string empty_str;
603  return empty_str;
604  }
605 
606  virtual ~backend() = default;
607  };
608 
610  {
611  public:
612  void register_profiles(const std::vector<hid_profile>& hid_profiles) override { _hid_profiles = hid_profiles; }
613  void open(const std::vector<hid_profile>& sensor_iio) override
614  {
615  for (auto&& dev : _dev) dev->open(sensor_iio);
616  }
617 
618  void close() override
619  {
620  for (auto&& dev : _dev) dev->close();
621  }
622 
623  void stop_capture() override
624  {
625  _dev.front()->stop_capture();
626  }
627 
628  void start_capture(hid_callback callback) override
629  {
630  _dev.front()->start_capture(callback);
631  }
632 
633  std::vector<hid_sensor> get_sensors() override
634  {
635  return _dev.front()->get_sensors();
636  }
637 
638  explicit multi_pins_hid_device(const std::vector<std::shared_ptr<hid_device>>& dev)
639  : _dev(dev)
640  {
641  }
642 
643  std::vector<uint8_t> get_custom_report_data(const std::string& custom_sensor_name,
644  const std::string& report_name,
645  custom_sensor_report_field report_field) override
646  {
647  return _dev.front()->get_custom_report_data(custom_sensor_name, report_name, report_field);
648  }
649 
650  private:
651  std::vector<std::shared_ptr<hid_device>> _dev;
652  std::vector<hid_profile> _hid_profiles;
653  };
654 
656  {
657  public:
658  explicit multi_pins_uvc_device(const std::vector<std::shared_ptr<uvc_device>>& dev)
659  : _dev(dev)
660  {}
661 
663  {
664  auto dev_index = get_dev_index_by_profiles(profile);
665  _configured_indexes.insert(dev_index);
666  _dev[dev_index]->probe_and_commit(profile, callback, buffers);
667  }
668 
669 
670  void stream_on(std::function<void(const notification& n)> error_handler = [](const notification& n){}) override
671  {
672  for (auto& elem : _configured_indexes)
673  {
674  _dev[elem]->stream_on(error_handler);
675  }
676  }
677  void start_callbacks() override
678  {
679  for (auto& elem : _configured_indexes)
680  {
681  _dev[elem]->start_callbacks();
682  }
683  }
684 
685  void stop_callbacks() override
686  {
687  for (auto& elem : _configured_indexes)
688  {
689  _dev[elem]->stop_callbacks();
690  }
691  }
692 
693  void close(stream_profile profile) override
694  {
695  auto dev_index = get_dev_index_by_profiles(profile);
696  _dev[dev_index]->close(profile);
697  _configured_indexes.erase(dev_index);
698  }
699 
701  {
702  for (auto& elem : _dev)
703  {
704  elem->set_power_state(state);
705  }
706  }
707 
708  power_state get_power_state() const override
709  {
710  return _dev.front()->get_power_state();
711  }
712 
713  void init_xu(const extension_unit& xu) override
714  {
715  _dev.front()->init_xu(xu);
716  }
717 
718  bool set_xu(const extension_unit& xu, uint8_t ctrl, const uint8_t* data, int len) override
719  {
720  return _dev.front()->set_xu(xu, ctrl, data, len);
721  }
722 
723  bool get_xu(const extension_unit& xu, uint8_t ctrl, uint8_t* data, int len) const override
724  {
725  return _dev.front()->get_xu(xu, ctrl, data, len);
726  }
727 
728  control_range get_xu_range(const extension_unit& xu, uint8_t ctrl, int len) const override
729  {
730  return _dev.front()->get_xu_range(xu, ctrl, len);
731  }
732 
733  bool get_pu(rs2_option opt, int32_t& value) const override
734  {
735  return _dev.front()->get_pu(opt, value);
736  }
737 
738  bool set_pu(rs2_option opt, int32_t value) override
739  {
740  return _dev.front()->set_pu(opt, value);
741  }
742 
744  {
745  return _dev.front()->get_pu_range(opt);
746  }
747 
748  std::vector<stream_profile> get_profiles() const override
749  {
750  std::vector<stream_profile> all_stream_profiles;
751  for (auto& elem : _dev)
752  {
753  auto pin_stream_profiles = elem->get_profiles();
754  all_stream_profiles.insert(all_stream_profiles.end(),
755  pin_stream_profiles.begin(), pin_stream_profiles.end());
756  }
757  return all_stream_profiles;
758  }
759 
760  std::string get_device_location() const override
761  {
762  return _dev.front()->get_device_location();
763  }
764 
766  {
767  return _dev.front()->get_usb_specification();
768  }
769 
770  void lock() const override
771  {
772  std::vector<uvc_device*> locked_dev;
773  try {
774  for (auto& elem : _dev)
775  {
776  elem->lock();
777  locked_dev.push_back(elem.get());
778  }
779  }
780  catch(...)
781  {
782  for (auto& elem : locked_dev)
783  {
784  elem->unlock();
785  }
786  throw;
787  }
788  }
789 
790  void unlock() const override
791  {
792  for (auto& elem : _dev)
793  {
794  elem->unlock();
795  }
796  }
797 
798  private:
800  {
801  uint32_t dev_index = 0;
802  for (auto& elem : _dev)
803  {
804  auto pin_stream_profiles = elem->get_profiles();
805  auto it = find(pin_stream_profiles.begin(), pin_stream_profiles.end(), profile);
806  if (it != pin_stream_profiles.end())
807  {
808  return dev_index;
809  }
810  ++dev_index;
811  }
812  throw std::runtime_error("profile not found");
813  }
814 
815  std::vector<std::shared_ptr<uvc_device>> _dev;
816  std::set<uint32_t> _configured_indexes;
817  };
818 
819  std::shared_ptr<backend> create_backend();
820 
821 
822 
824  {
825  public:
826  virtual void start(device_changed_callback callback) = 0;
827  virtual void stop() = 0;
828  virtual bool is_stopped() const = 0;
829  virtual ~device_watcher() {};
830  };
831  }
832 
833  double monotonic_to_realtime(double monotonic);
834 
835 } // namespace librealsense
static const textual_icon lock
Definition: model-views.h:219
std::vector< std::shared_ptr< uvc_device > > _dev
Definition: backend.h:815
const int POLLING_DEVICES_INTERVAL_MS
Definition: backend.h:32
constexpr uint8_t uvc_header_mipi_size
Definition: backend.h:173
static const textual_icon unlock
Definition: model-views.h:238
bool set_xu(const extension_unit &xu, uint8_t ctrl, const uint8_t *data, int len) override
Definition: backend.h:718
std::string get_device_location() const override
Definition: backend.h:760
std::vector< uint8_t > max
Definition: backend.h:88
std::vector< hid_sensor > get_sensors() override
Definition: backend.h:633
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:415
std::vector< playback_device_info > playback_devices
Definition: backend.h:536
constexpr uint8_t uvc_header_size
Definition: backend.h:171
usb_spec get_usb_specification() const override
Definition: backend.h:765
GLfloat value
void init_xu(const extension_unit &xu) override
Definition: backend.h:430
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:528
backend_device_group(const std::vector< playback_device_info > &playback_devices)
Definition: backend.h:531
unsigned short uint16_t
Definition: stdint.h:79
retry_controls_work_around(std::shared_ptr< uvc_device > dev)
Definition: backend.h:392
control_range get_xu_range(const extension_unit &xu, uint8_t ctrl, int len) const override
Definition: backend.h:728
unsigned char uint8_t
Definition: stdint.h:78
void set_power_state(power_state state) override
Definition: backend.h:420
uint32_t get_dev_index_by_profiles(const stream_profile &profile) const
Definition: backend.h:799
static const textual_icon stop
Definition: model-views.h:226
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:643
bool get_xu(const extension_unit &xu, uint8_t ctrl, uint8_t *data, int len) const override
Definition: backend.h:447
std::shared_ptr< backend > create_backend()
GLenum GLuint id
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
def info(name, value, persistent=False)
Definition: test.py:327
const uint16_t MAX_RETRIES
Definition: backend.h:28
bool get_xu(const extension_unit &xu, uint8_t ctrl, uint8_t *data, int len) const override
Definition: backend.h:723
bool set_xu(const extension_unit &xu, uint8_t ctrl, const uint8_t *data, int len) override
Definition: backend.h:435
GLboolean GLboolean GLboolean GLboolean a
std::vector< hid_device_info > hid_devices
Definition: backend.h:535
multi_pins_uvc_device(const std::vector< std::shared_ptr< uvc_device >> &dev)
Definition: backend.h:658
void probe_and_commit(stream_profile profile, frame_callback callback, int buffers) override
Definition: backend.h:395
bool get_pu(rs2_option opt, int32_t &value) const override
Definition: backend.h:464
const int DISCONNECT_PERIOD_MS
Definition: backend.h:31
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
Exposes RealSense structs.
const uint16_t DELAY_FOR_RETRIES
Definition: backend.h:30
std::function< void(backend_device_group old, backend_device_group curr)> device_changed_callback
Definition: backend.h:582
unsigned int uint32_t
Definition: stdint.h:80
bool operator<(const stream_profile &lhs, const stream_profile &rhs)
Definition: src/types.h:572
void init_xu(const extension_unit &xu) override
Definition: backend.h:713
control_range get_xu_range(const extension_unit &xu, uint8_t ctrl, int len) const override
Definition: backend.h:459
std::vector< hid_profile > _hid_profiles
Definition: backend.h:652
void register_profiles(const std::vector< hid_profile > &hid_profiles) override
Definition: backend.h:612
void stream_on(std::function< void(const notification &n)> error_handler=[](const notification &n){}) override
Definition: backend.h:400
void probe_and_commit(stream_profile profile, frame_callback callback, int buffers) override
Definition: backend.h:662
def find(dir, mask)
Definition: file.py:45
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:651
void close(stream_profile profile) override
Definition: backend.h:693
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:700
Exposes sensor options functionality for C compilers.
const GLuint * buffers
std::string get_device_location() const override
Definition: backend.h:498
std::vector< stream_profile > get_profiles() const override
Definition: backend.h:493
bool set_pu(rs2_option opt, int32_t value) override
Definition: backend.h:738
void start_capture(hid_callback callback) override
Definition: backend.h:628
std::function< void(const notification &n)> _error_handler
Definition: backend.h:386
GLboolean GLboolean GLboolean b
bool get_pu(rs2_option opt, int32_t &value) const override
Definition: backend.h:733
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:184
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:670
rs2_time_t get_time() const override
Definition: backend.h:106
static auto it
std::vector< usb_device_info > usb_devices
Definition: backend.h:534
multi_pins_hid_device(const std::vector< std::shared_ptr< hid_device >> &dev)
Definition: backend.h:638
GLint GLsizei count
std::vector< uint8_t > def
Definition: backend.h:90
std::shared_ptr< uvc_device > _dev
Definition: backend.h:512
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:525
control_range get_pu_range(rs2_option opt) const override
Definition: backend.h:743
power_state get_power_state() const override
Definition: backend.h:425
signed int int32_t
Definition: stdint.h:77
std::function< void(const sensor_data &)> hid_callback
Definition: backend.h:335
std::vector< uvc_device_info > uvc_devices
Definition: backend.h:533
power_state get_power_state() const override
Definition: backend.h:708
bool operator==(const stream_profile &a, const stream_profile &b)
Definition: backend.h:138
const uint8_t DEFAULT_V4L2_FRAME_BUFFERS
Definition: backend.h:29
std::vector< uint8_t > step
Definition: backend.h:89
usb_spec get_usb_specification() const override
Definition: backend.h:503
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:522
std::vector< stream_profile > get_profiles() const override
Definition: backend.h:748
double rs2_time_t
Definition: rs_types.h:301
constexpr uint8_t hid_header_size
Definition: backend.h:172
void open(const std::vector< hid_profile > &sensor_iio) override
Definition: backend.h:613
bool set_pu(rs2_option opt, int32_t value) override
Definition: backend.h:476
control_range get_pu_range(rs2_option opt) const override
Definition: backend.h:488
double get_time()
Definition: rs_internal.hpp:62
Definition: parser.hpp:153
virtual std::string get_device_serial(uint16_t device_vid, uint16_t device_pid, const std::string &device_uid) const
Definition: backend.h:600


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