context.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 #ifdef _MSC_VER
4 #if (_MSC_VER <= 1800) // constexpr is not supported in MSVC2013
5 #error( "Librealsense requires MSVC2015 or later to build. Compilation will be aborted" )
6 #endif
7 #endif
8 
9 #include <array>
10 #include <chrono>
11 #include "ivcam/sr300.h"
12 #include "ds5/ds5-factory.h"
13 #include "l500/l500-factory.h"
14 #include "ds5/ds5-timestamp.h"
15 #include "backend.h"
16 #include "mock/recorder.h"
17 #include <media/ros/ros_reader.h>
18 #include "types.h"
19 #include "stream.h"
20 #include "environment.h"
21 #include "context.h"
23 
24 #ifdef WITH_TRACKING
25 #include "tm2/tm-info.h"
26 #endif
27 
28 template<unsigned... Is> struct seq{};
29 template<unsigned N, unsigned... Is>
30 struct gen_seq : gen_seq<N-1, N-1, Is...>{};
31 template<unsigned... Is>
32 struct gen_seq<0, Is...> : seq<Is...>{};
33 
34 template<unsigned N1, unsigned... I1, unsigned N2, unsigned... I2>
35 constexpr std::array<char const, N1+N2-1> concat(char const (&a1)[N1], char const (&a2)[N2], seq<I1...>, seq<I2...>){
36  return {{ a1[I1]..., a2[I2]... }};
37 }
38 
39 template<unsigned N1, unsigned N2>
40 constexpr std::array<char const, N1+N2-1> concat(char const (&a1)[N1], char const (&a2)[N2]){
41  return concat(a1, a2, gen_seq<N1-1>{}, gen_seq<N2>{});
42 }
43 
44 // The string is used to retrieve the version embedded into .so file on Linux
45 constexpr auto rs2_api_version = concat("VERSION: ",RS2_API_VERSION_STR);
46 
47 template<>
48 bool contains(const std::shared_ptr<librealsense::device_info>& first,
49  const std::shared_ptr<librealsense::device_info>& second)
50 {
51  auto first_data = first->get_device_data();
52  auto second_data = second->get_device_data();
53 
54  for (auto&& uvc : first_data.uvc_devices)
55  {
56  if (std::find(second_data.uvc_devices.begin(),
57  second_data.uvc_devices.end(), uvc) ==
58  second_data.uvc_devices.end())
59  return false;
60  }
61  for (auto&& usb : first_data.usb_devices)
62  {
63  if (std::find(second_data.usb_devices.begin(),
64  second_data.usb_devices.end(), usb) ==
65  second_data.usb_devices.end())
66  return false;
67  }
68  for (auto&& hid : first_data.hid_devices)
69  {
70  if (std::find(second_data.hid_devices.begin(),
71  second_data.hid_devices.end(), hid) ==
72  second_data.hid_devices.end())
73  return false;
74  }
75  for (auto&& pd : first_data.playback_devices)
76  {
77  if (std::find(second_data.playback_devices.begin(),
78  second_data.playback_devices.end(), pd) ==
79  second_data.playback_devices.end())
80  return false;
81  }
82  return true;
83 }
84 
85 namespace librealsense
86 {
87  const std::map<uint32_t, rs2_format> platform_color_fourcc_to_rs2_format = {
88  {rs_fourcc('Y','U','Y','2'), RS2_FORMAT_YUYV},
89  {rs_fourcc('Y','U','Y','V'), RS2_FORMAT_YUYV},
90  {rs_fourcc('M','J','P','G'), RS2_FORMAT_MJPEG},
91  };
92  const std::map<uint32_t, rs2_stream> platform_color_fourcc_to_rs2_stream = {
93  {rs_fourcc('Y','U','Y','2'), RS2_STREAM_COLOR},
94  {rs_fourcc('Y','U','Y','V'), RS2_STREAM_COLOR},
95  {rs_fourcc('M','J','P','G'), RS2_STREAM_COLOR},
96  };
97 
99  const char* filename,
100  const char* section,
102  std::string min_api_version)
103  : _devices_changed_callback(nullptr, [](rs2_devices_changed_callback*){})
104  {
105  static bool version_logged=false;
106  if (!version_logged)
107  {
108  version_logged = true;
109  LOG_DEBUG("Librealsense " << std::string(std::begin(rs2_api_version),std::end(rs2_api_version)));
110  }
111 
112  switch(type)
113  {
116  break;
118  _backend = std::make_shared<platform::record_backend>(platform::create_backend(), filename, section, mode);
119  break;
121  _backend = std::make_shared<platform::playback_backend>(filename, section, min_api_version);
122  break;
123  // Strongly-typed enum. Default is redundant
124  }
125 
126  environment::get_instance().set_time_service(_backend->create_time_service());
127 
128  _device_watcher = _backend->create_device_watcher();
129  assert(_device_watcher->is_stopped());
130  }
131 
132 
133  class recovery_info : public device_info
134  {
135  public:
136  std::shared_ptr<device_interface> create(std::shared_ptr<context>, bool) const override
137  {
138  throw unrecoverable_exception(RECOVERY_MESSAGE,
140  }
141 
143  {
144  return pid == 0x0ADB || pid == 0x0AB3;
145  }
146 
147  static std::vector<std::shared_ptr<device_info>> pick_recovery_devices(
148  std::shared_ptr<context> ctx,
149  const std::vector<platform::usb_device_info>& usb_devices)
150  {
151  std::vector<std::shared_ptr<device_info>> list;
152  for (auto&& usb : usb_devices)
153  {
154  if (is_recovery_pid(usb.pid))
155  {
156  list.push_back(std::make_shared<recovery_info>(ctx, usb));
157  }
158  }
159  return list;
160  }
161 
162  explicit recovery_info(std::shared_ptr<context> ctx, platform::usb_device_info dfu)
163  : device_info(ctx), _dfu(std::move(dfu)) {}
164 
166  {
167  return platform::backend_device_group({ _dfu });
168  }
169 
170  private:
172  const char* RECOVERY_MESSAGE = "Selected RealSense device is in recovery mode!\nEither perform a firmware update or reconnect the camera to fall-back to last working firmware if available!";
173  };
174 
176  {
177  public:
178  std::shared_ptr<device_interface> create(std::shared_ptr<context>, bool) const override;
179 
180  static std::vector<std::shared_ptr<device_info>> pick_uvc_devices(
181  const std::shared_ptr<context>& ctx,
182  const std::vector<platform::uvc_device_info>& uvc_devices)
183  {
184  std::vector<std::shared_ptr<device_info>> list;
185  auto groups = group_devices_by_unique_id(uvc_devices);
186 
187  for (auto&& g : groups)
188  {
189  if (g.front().vid != VID_INTEL_CAMERA)
190  list.push_back(std::make_shared<platform_camera_info>(ctx, g));
191  }
192  return list;
193  }
194 
195  explicit platform_camera_info(std::shared_ptr<context> ctx,
196  std::vector<platform::uvc_device_info> uvcs)
197  : device_info(ctx), _uvcs(std::move(uvcs)) {}
198 
200  {
202  }
203 
204  private:
205  std::vector<platform::uvc_device_info> _uvcs;
206  };
207 
209  {
210  public:
212  std::shared_ptr<uvc_sensor> uvc_sensor)
213  : synthetic_sensor("RGB Camera", uvc_sensor, owner,platform_color_fourcc_to_rs2_format,platform_color_fourcc_to_rs2_stream),
214  _default_stream(new stream(RS2_STREAM_COLOR))
215  {
216  }
217 
219  {
221 
223 
224  for (auto&& p : results)
225  {
226  // Register stream types
227  assign_stream(_default_stream, p);
229  }
230 
231  return results;
232  }
233 
234 
235  private:
236  std::shared_ptr<stream_interface> _default_stream;
237  };
238 
239  class platform_camera : public device
240  {
241  public:
242  platform_camera(const std::shared_ptr<context>& ctx,
243  const std::vector<platform::uvc_device_info>& uvc_infos,
245  bool register_device_notifications)
246  : device(ctx, group, register_device_notifications)
247  {
248  std::vector<std::shared_ptr<platform::uvc_device>> devs;
249  for (auto&& info : uvc_infos)
250  devs.push_back(ctx->get_backend().create_uvc_device(info));
251 
252  std::unique_ptr<frame_timestamp_reader> host_timestamp_reader_backup(new ds5_timestamp_reader(environment::get_instance().get_time_service()));
253  auto raw_color_ep = std::make_shared<uvc_sensor>("Raw RGB Camera",
254  std::make_shared<platform::multi_pins_uvc_device>(devs),
255  std::unique_ptr<frame_timestamp_reader>(new ds5_timestamp_reader_from_metadata(std::move(host_timestamp_reader_backup))),
256  this);
257  auto color_ep = std::make_shared<platform_camera_sensor>(this, raw_color_ep);
258  add_sensor(color_ep);
259 
260  register_info(RS2_CAMERA_INFO_NAME, "Platform Camera");
261  std::string pid_str(to_string() << std::setfill('0') << std::setw(4) << std::hex << uvc_infos.front().pid);
262  std::transform(pid_str.begin(), pid_str.end(), pid_str.begin(), ::toupper);
263 
264  using namespace platform;
265  auto usb_mode = raw_color_ep->get_usb_specification();
266  std::string usb_type_str("USB");
267  if (usb_spec_names.count(usb_mode) && (usb_undefined != usb_mode))
268  usb_type_str = usb_spec_names.at(usb_mode);
269 
270  register_info(RS2_CAMERA_INFO_USB_TYPE_DESCRIPTOR, usb_type_str);
271  register_info(RS2_CAMERA_INFO_SERIAL_NUMBER, uvc_infos.front().unique_id);
272  register_info(RS2_CAMERA_INFO_PHYSICAL_PORT, uvc_infos.front().device_path);
273  register_info(RS2_CAMERA_INFO_PRODUCT_ID, pid_str);
274 
275  color_ep->register_processing_block(processing_block_factory::create_pbf_vector<yuy2_converter>(RS2_FORMAT_YUYV, map_supported_color_formats(RS2_FORMAT_YUYV), RS2_STREAM_COLOR));
276  color_ep->register_processing_block({ {RS2_FORMAT_MJPEG} }, { {RS2_FORMAT_RGB8, RS2_STREAM_COLOR} }, []() { return std::make_shared<mjpeg_converter>(RS2_FORMAT_RGB8); });
277  color_ep->register_processing_block(processing_block_factory::create_id_pbf(RS2_FORMAT_MJPEG, RS2_STREAM_COLOR));
278 
279  // Timestamps are given in units set by device which may vary among the OEM vendors.
280  // For consistent (msec) measurements use "time of arrival" metadata attribute
282 
283  color_ep->try_register_pu(RS2_OPTION_BACKLIGHT_COMPENSATION);
284  color_ep->try_register_pu(RS2_OPTION_BRIGHTNESS);
285  color_ep->try_register_pu(RS2_OPTION_CONTRAST);
286  color_ep->try_register_pu(RS2_OPTION_EXPOSURE);
287  color_ep->try_register_pu(RS2_OPTION_GAMMA);
288  color_ep->try_register_pu(RS2_OPTION_HUE);
289  color_ep->try_register_pu(RS2_OPTION_SATURATION);
290  color_ep->try_register_pu(RS2_OPTION_SHARPNESS);
291  color_ep->try_register_pu(RS2_OPTION_WHITE_BALANCE);
292  color_ep->try_register_pu(RS2_OPTION_ENABLE_AUTO_EXPOSURE);
293  color_ep->try_register_pu(RS2_OPTION_ENABLE_AUTO_WHITE_BALANCE);
294  }
295 
296  virtual rs2_intrinsics get_intrinsics(unsigned int, const stream_profile&) const
297  {
298  return rs2_intrinsics {};
299  }
300 
301  std::vector<tagged_profile> get_profiles_tags() const override
302  {
303  std::vector<tagged_profile> markers;
305  return markers;
306  }
307  };
308 
309  std::shared_ptr<device_interface> platform_camera_info::create(std::shared_ptr<context> ctx,
310  bool register_device_notifications) const
311  {
312  return std::make_shared<platform_camera>(ctx, _uvcs, this->get_device_data(), register_device_notifications);
313  }
314 
316  {
317  _device_watcher->stop(); //ensure that the device watcher will stop before the _devices_changed_callback will be deleted
318  }
319 
320  std::vector<std::shared_ptr<device_info>> context::query_devices(int mask) const
321  {
322 
323  platform::backend_device_group devices(_backend->query_uvc_devices(), _backend->query_usb_devices(), _backend->query_hid_devices());
325  }
326 
327  std::vector<std::shared_ptr<device_info>> context::create_devices(platform::backend_device_group devices,
328  const std::map<std::string, std::weak_ptr<device_info>>& playback_devices,
329  int mask) const
330  {
331  std::vector<std::shared_ptr<device_info>> list;
332 
333  auto t = const_cast<context*>(this); // While generally a bad idea, we need to provide mutable reference to the devices
334  // to allow them to modify context later on
335  auto ctx = t->shared_from_this();
336 
337  if (mask & RS2_PRODUCT_LINE_D400)
338  {
339  auto ds5_devices = ds5_info::pick_ds5_devices(ctx, devices);
340  std::copy(begin(ds5_devices), end(ds5_devices), std::back_inserter(list));
341  }
342 
343  if( mask & RS2_PRODUCT_LINE_L500 )
344  {
345  auto l500_devices = l500_info::pick_l500_devices(ctx, devices);
346  std::copy(begin(l500_devices), end(l500_devices), std::back_inserter(list));
347  }
348 
349  if (mask & RS2_PRODUCT_LINE_SR300)
350  {
351  auto sr300_devices = sr300_info::pick_sr300_devices(ctx, devices.uvc_devices, devices.usb_devices);
352  std::copy(begin(sr300_devices), end(sr300_devices), std::back_inserter(list));
353  }
354 
355 #ifdef WITH_TRACKING
356  if (mask & RS2_PRODUCT_LINE_T200)
357  {
358  auto tm2_devices = tm2_info::pick_tm2_devices(ctx, devices.usb_devices);
359  std::copy(begin(tm2_devices), end(tm2_devices), std::back_inserter(list));
360  }
361 #endif
362  // Supported recovery devices
363  if (mask & RS2_PRODUCT_LINE_D400 || mask & RS2_PRODUCT_LINE_SR300 || mask & RS2_PRODUCT_LINE_L500)
364  {
365  auto recovery_devices = fw_update_info::pick_recovery_devices(ctx, devices.usb_devices, mask);
366  std::copy(begin(recovery_devices), end(recovery_devices), std::back_inserter(list));
367  }
368 
369  if (mask & RS2_PRODUCT_LINE_NON_INTEL)
370  {
371  auto uvc_devices = platform_camera_info::pick_uvc_devices(ctx, devices.uvc_devices);
372  std::copy(begin(uvc_devices), end(uvc_devices), std::back_inserter(list));
373  }
374 
375  for (auto&& item : playback_devices)
376  {
377  if (auto dev = item.second.lock())
378  list.push_back(dev);
379  }
380 
381  if (list.size())
382  LOG_INFO( "Found " << list.size() << " RealSense devices (mask 0x" << std::hex << mask << ")" );
383  return list;
384  }
385 
386 
389  const std::map<std::string, std::weak_ptr<device_info>>& old_playback_devices,
390  const std::map<std::string, std::weak_ptr<device_info>>& new_playback_devices)
391  {
392  auto old_list = create_devices(old, old_playback_devices, RS2_PRODUCT_LINE_ANY);
393  auto new_list = create_devices(curr, new_playback_devices, RS2_PRODUCT_LINE_ANY);
394 
395  if (librealsense::list_changed<std::shared_ptr<device_info>>(old_list, new_list, [](std::shared_ptr<device_info> first, std::shared_ptr<device_info> second) {return *first == *second; }))
396  {
397  std::vector<rs2_device_info> rs2_devices_info_added;
398  std::vector<rs2_device_info> rs2_devices_info_removed;
399 
400  auto devices_info_removed = subtract_sets(old_list, new_list);
401 
402  for (size_t i = 0; i < devices_info_removed.size(); i++)
403  {
404  rs2_devices_info_removed.push_back({ shared_from_this(), devices_info_removed[i] });
405  LOG_DEBUG("\nDevice disconnected:\n\n" << std::string(devices_info_removed[i]->get_device_data()));
406  }
407 
408  auto devices_info_added = subtract_sets(new_list, old_list);
409  for (size_t i = 0; i < devices_info_added.size(); i++)
410  {
411  rs2_devices_info_added.push_back({ shared_from_this(), devices_info_added[i] });
412  LOG_DEBUG("\nDevice connected:\n\n" << std::string(devices_info_added[i]->get_device_data()));
413  }
414 
415  std::map<uint64_t, devices_changed_callback_ptr> devices_changed_callbacks;
416  {
417  std::lock_guard<std::mutex> lock(_devices_changed_callbacks_mtx);
418  devices_changed_callbacks = _devices_changed_callbacks;
419  }
420 
421  for (auto& kvp : devices_changed_callbacks)
422  {
423  try
424  {
425  kvp.second->on_devices_changed(new rs2_device_list({ shared_from_this(), rs2_devices_info_removed }),
426  new rs2_device_list({ shared_from_this(), rs2_devices_info_added }));
427  }
428  catch (...)
429  {
430  LOG_ERROR("Exception thrown from user callback handler");
431  }
432  }
433 
434  raise_devices_changed(rs2_devices_info_removed, rs2_devices_info_added);
435  }
436  }
437  void context::raise_devices_changed(const std::vector<rs2_device_info>& removed, const std::vector<rs2_device_info>& added)
438  {
440  {
441  try
442  {
443  _devices_changed_callback->on_devices_changed(new rs2_device_list({ shared_from_this(), removed }),
444  new rs2_device_list({ shared_from_this(), added }));
445  }
446  catch (...)
447  {
448  LOG_ERROR("Exception thrown from user callback handler");
449  }
450  }
451  }
452 
454  {
456  {
458  });
459  }
460 
462  {
463  std::lock_guard<std::mutex> lock(_devices_changed_callbacks_mtx);
464  auto callback_id = unique_id::generate_id();
465  _devices_changed_callbacks.insert(std::make_pair(callback_id, std::move(callback)));
466 
467  if (_device_watcher->is_stopped())
468  {
470  }
471 
472  return callback_id;
473  }
474 
476  {
477  std::lock_guard<std::mutex> lock(_devices_changed_callbacks_mtx);
478  _devices_changed_callbacks.erase(cb_id);
479 
480  if (_devices_changed_callback == nullptr && _devices_changed_callbacks.size() == 0) // There are no register callbacks any more _device_watcher can be stopped
481  {
482  _device_watcher->stop();
483  }
484  }
485 
487  {
488  std::lock_guard<std::mutex> lock(_devices_changed_callbacks_mtx);
490 
491  if (_device_watcher->is_stopped())
492  {
494  }
495  }
496 
497  std::vector<platform::uvc_device_info> filter_by_product(const std::vector<platform::uvc_device_info>& devices, const std::set<uint16_t>& pid_list)
498  {
499  std::vector<platform::uvc_device_info> result;
500  for (auto&& info : devices)
501  {
502  if (pid_list.count(info.pid))
503  result.push_back(info);
504  }
505  return result;
506  }
507 
508  // TODO: Make template
509  std::vector<platform::usb_device_info> filter_by_product(const std::vector<platform::usb_device_info>& devices, const std::set<uint16_t>& pid_list)
510  {
511  std::vector<platform::usb_device_info> result;
512  for (auto&& info : devices)
513  {
514  if (pid_list.count(info.pid))
515  result.push_back(info);
516  }
517  return result;
518  }
519 
520  std::vector<std::pair<std::vector<platform::uvc_device_info>, std::vector<platform::hid_device_info>>> group_devices_and_hids_by_unique_id(
521  const std::vector<std::vector<platform::uvc_device_info>>& devices,
522  const std::vector<platform::hid_device_info>& hids)
523  {
524  std::vector<std::pair<std::vector<platform::uvc_device_info>, std::vector<platform::hid_device_info>>> results;
525  uint16_t vid;
526  uint16_t pid;
527 
528  for (auto&& dev : devices)
529  {
530  std::vector<platform::hid_device_info> hid_group;
531  auto unique_id = dev.front().unique_id;
532  auto device_serial = dev.front().serial;
533 
534  for (auto&& hid : hids)
535  {
536  if( ! hid.unique_id.empty() )
537  {
538  std::stringstream(hid.vid) >> std::hex >> vid;
539  std::stringstream(hid.pid) >> std::hex >> pid;
540 
541  if (hid.unique_id == unique_id)
542  {
543  hid_group.push_back(hid);
544  }
545  }
546  }
547  results.push_back(std::make_pair(dev, hid_group));
548  }
549  return results;
550  }
551 
552  std::shared_ptr<playback_device_info> context::add_device(const std::string& file)
553  {
554  auto it = _playback_devices.find(file);
555  if (it != _playback_devices.end() && it->second.lock())
556  {
557  //Already exists
558  throw librealsense::invalid_value_exception(to_string() << "File \"" << file << "\" already loaded to context");
559  }
560  auto playback_dev = std::make_shared<playback_device>(shared_from_this(), std::make_shared<ros_reader>(file, shared_from_this()));
561  auto dinfo = std::make_shared<playback_device_info>(playback_dev);
562  auto prev_playback_devices = _playback_devices;
563  _playback_devices[file] = dinfo;
564  on_device_changed({}, {}, prev_playback_devices, _playback_devices);
565  return std::move(dinfo);
566  }
567 
568  void context::add_software_device(std::shared_ptr<device_info> dev)
569  {
570  auto file = dev->get_device_data().playback_devices.front().file_path;
571 
572  auto it = _playback_devices.find(file);
573  if (it != _playback_devices.end() && it->second.lock())
574  {
575  //Already exists
576  throw librealsense::invalid_value_exception(to_string() << "File \"" << file << "\" already loaded to context");
577  }
578  auto prev_playback_devices = _playback_devices;
579  _playback_devices[file] = dev;
580  on_device_changed({}, {}, prev_playback_devices, _playback_devices);
581  }
582 
583  void context::remove_device(const std::string& file)
584  {
585  auto it = _playback_devices.find(file);
586  if(it == _playback_devices.end() || !it->second.lock())
587  {
588  //Not found
589  return;
590  }
591  auto prev_playback_devices =_playback_devices;
592  _playback_devices.erase(it);
593  on_device_changed({},{}, prev_playback_devices, _playback_devices);
594  }
595 
596 #if WITH_TRACKING
597  void context::unload_tracking_module()
598  {
599  }
600 #endif
601 
602  std::vector<std::vector<platform::uvc_device_info>> group_devices_by_unique_id(const std::vector<platform::uvc_device_info>& devices)
603  {
604  std::map<std::string, std::vector<platform::uvc_device_info>> map;
605  for (auto&& info : devices)
606  {
607  map[info.unique_id].push_back(info);
608  }
609  std::vector<std::vector<platform::uvc_device_info>> result;
610  for (auto&& kvp : map)
611  {
612  result.push_back(kvp.second);
613  }
614  return result;
615  }
616 
617  // TODO: Sergey
618  // Make template
619  void trim_device_list(std::vector<platform::usb_device_info>& devices, const std::vector<platform::usb_device_info>& chosen)
620  {
621  if (chosen.empty())
622  return;
623 
624  auto was_chosen = [&chosen](const platform::usb_device_info& info)
625  {
626  return find(chosen.begin(), chosen.end(), info) != chosen.end();
627  };
628  devices.erase(std::remove_if(devices.begin(), devices.end(), was_chosen), devices.end());
629  }
630 
631  void trim_device_list(std::vector<platform::uvc_device_info>& devices, const std::vector<platform::uvc_device_info>& chosen)
632  {
633  if (chosen.empty())
634  return;
635 
636  auto was_chosen = [&chosen](const platform::uvc_device_info& info)
637  {
638  return find(chosen.begin(), chosen.end(), info) != chosen.end();
639  };
640  devices.erase(std::remove_if(devices.begin(), devices.end(), was_chosen), devices.end());
641  }
642 
643  bool mi_present(const std::vector<platform::uvc_device_info>& devices, uint32_t mi)
644  {
645  for (auto&& info : devices)
646  {
647  if (info.mi == mi)
648  return true;
649  }
650  return false;
651  }
652 
653  platform::uvc_device_info get_mi(const std::vector<platform::uvc_device_info>& devices, uint32_t mi)
654  {
655  for (auto&& info : devices)
656  {
657  if (info.mi == mi)
658  return info;
659  }
660  throw invalid_value_exception("Interface not found!");
661  }
662 
663  std::vector<platform::uvc_device_info> filter_by_mi(const std::vector<platform::uvc_device_info>& devices, uint32_t mi)
664  {
665  std::vector<platform::uvc_device_info> results;
666  for (auto&& info : devices)
667  {
668  if (info.mi == mi)
669  results.push_back(info);
670  }
671  return results;
672  }
673 }
674 
675 using namespace librealsense;
GLboolean GLboolean g
void on_device_changed(platform::backend_device_group old, platform::backend_device_group curr, const std::map< std::string, std::weak_ptr< device_info >> &old_playback_devices, const std::map< std::string, std::weak_ptr< device_info >> &new_playback_devices)
Definition: context.cpp:387
platform_camera_info(std::shared_ptr< context > ctx, std::vector< platform::uvc_device_info > uvcs)
Definition: context.cpp:195
static const textual_icon lock
Definition: model-views.h:219
context
Definition: test.py:30
#define LOG_ERROR(...)
Definition: easyloggingpp.h:58
platform_camera(const std::shared_ptr< context > &ctx, const std::vector< platform::uvc_device_info > &uvc_infos, const platform::backend_device_group &group, bool register_device_notifications)
Definition: context.cpp:242
GLuint GLuint end
static bool is_recovery_pid(uint16_t pid)
Definition: context.cpp:142
std::vector< std::shared_ptr< device_info > > create_devices(platform::backend_device_group devices, const std::map< std::string, std::weak_ptr< device_info >> &playback_devices, int mask) const
Definition: context.cpp:327
std::vector< platform::uvc_device_info > filter_by_product(const std::vector< platform::uvc_device_info > &devices, const std::set< uint16_t > &pid_list)
Definition: context.cpp:497
std::map< std::string, std::weak_ptr< device_info > > _playback_devices
Definition: context.h:147
void trim_device_list(std::vector< platform::usb_device_info > &devices, const std::vector< platform::usb_device_info > &chosen)
Definition: context.cpp:619
rs2_recording_mode
Definition: rs_internal.h:34
GLint GLuint mask
virtual stream_profiles init_stream_profiles() override
Definition: sensor.cpp:1395
std::vector< std::shared_ptr< device_info > > query_devices(int mask) const
Definition: context.cpp:320
const uint16_t VID_INTEL_CAMERA
Definition: usb-types.h:41
void register_same_extrinsics(const stream_interface &from, const stream_interface &to)
Definition: environment.cpp:23
unsigned short uint16_t
Definition: stdint.h:79
static const std::map< usb_spec, std::string > usb_spec_names
Definition: usb-types.h:124
bool Is(std::shared_ptr< P > ptr)
Definition: extension.h:100
#define LOG_DEBUG(...)
Definition: easyloggingpp.h:55
Definition: context.cpp:28
std::shared_ptr< backend > create_backend()
std::mutex _devices_changed_callbacks_mtx
Definition: context.h:153
std::shared_ptr< device_interface > create(std::shared_ptr< context >, bool) const override
Definition: context.cpp:309
virtual rs2_intrinsics get_intrinsics(unsigned int, const stream_profile &) const
Definition: context.cpp:296
GLdouble t
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
void remove_device(const std::string &file)
Definition: context.cpp:583
Definition: parser.hpp:157
def info(name, value, persistent=False)
Definition: test.py:327
#define RS2_PRODUCT_LINE_NON_INTEL
Definition: rs_context.h:93
not_this_one begin(...)
GLenum mode
platform::usb_device_info _dfu
Definition: context.cpp:171
std::vector< tagged_profile > get_profiles_tags() const override
Definition: context.cpp:301
bool contains(const std::shared_ptr< librealsense::device_info > &first, const std::shared_ptr< librealsense::device_info > &second)
Definition: context.cpp:48
std::vector< std::pair< std::vector< platform::uvc_device_info >, std::vector< platform::hid_device_info > > > group_devices_and_hids_by_unique_id(const std::vector< std::vector< platform::uvc_device_info >> &devices, const std::vector< platform::hid_device_info > &hids)
Definition: context.cpp:520
std::vector< std::vector< platform::uvc_device_info > > group_devices_by_unique_id(const std::vector< platform::uvc_device_info > &devices)
Definition: context.cpp:602
double p[GRIDW][GRIDH]
Definition: wave.c:109
#define assert(condition)
Definition: lz4.c:245
std::vector< std::shared_ptr< T > > subtract_sets(const std::vector< std::shared_ptr< T >> &first, const std::vector< std::shared_ptr< T >> &second)
Definition: src/types.h:1518
std::vector< platform::uvc_device_info > _uvcs
Definition: context.cpp:205
unsigned int uint32_t
Definition: stdint.h:80
#define RS2_PRODUCT_LINE_D400
Definition: rs_context.h:94
devices
Definition: test-fg.py:9
uint32_t rs_fourcc(const T a, const T b, const T c, const T d)
Definition: src/types.h:1459
void set_time_service(std::shared_ptr< platform::time_service > ts)
platform::uvc_device_info get_mi(const std::vector< platform::uvc_device_info > &devices, uint32_t mi)
Definition: context.cpp:653
static processing_block_factory create_id_pbf(rs2_format format, rs2_stream stream, int idx=0)
recovery_info(std::shared_ptr< context > ctx, platform::usb_device_info dfu)
Definition: context.cpp:162
platform_camera_sensor(device *owner, std::shared_ptr< uvc_sensor > uvc_sensor)
Definition: context.cpp:211
def find(dir, mask)
Definition: file.py:45
def callback(frame)
Definition: t265_stereo.py:91
unsigned __int64 uint64_t
Definition: stdint.h:90
stream_profiles init_stream_profiles() override
Definition: context.cpp:218
GLint first
std::shared_ptr< md_attribute_parser_base > make_uvc_header_parser(Attribute St::*attribute, attrib_modifyer mod=nullptr)
A utility function to create UVC metadata header parser.
#define RS2_PRODUCT_LINE_L500
Definition: rs_context.h:96
#define RS2_PRODUCT_LINE_T200
Definition: rs_context.h:97
std::shared_ptr< platform::device_watcher > _device_watcher
Definition: context.h:145
static environment & get_instance()
extrinsics_graph & get_extrinsics_graph()
void start_device_watcher()
Definition: context.cpp:453
float3 transform(const rs2_extrinsics *extrin, const float3 &point)
Definition: pointcloud.cpp:47
#define RS2_PRODUCT_LINE_ANY
Definition: rs_context.h:91
LOG_INFO("Log message using LOG_INFO()")
platform::backend_device_group get_device_data() const override
Definition: context.cpp:199
constexpr std::array< char const, N1+N2-1 > concat(char const (&a1)[N1], char const (&a2)[N2], seq< I1... >, seq< I2... >)
Definition: context.cpp:35
static std::vector< std::shared_ptr< device_info > > pick_recovery_devices(std::shared_ptr< context > ctx, const std::vector< platform::usb_device_info > &usb_devices, int mask)
platform::backend_device_group get_device_data() const override
Definition: context.cpp:165
static auto it
GLenum type
void add_software_device(std::shared_ptr< device_info > software_device)
Definition: context.cpp:568
static std::vector< std::shared_ptr< device_info > > pick_ds5_devices(std::shared_ptr< context > ctx, platform::backend_device_group &gproup)
std::vector< usb_device_info > usb_devices
Definition: backend.h:534
void raise_devices_changed(const std::vector< rs2_device_info > &removed, const std::vector< rs2_device_info > &added)
Definition: context.cpp:437
#define RS2_API_VERSION_STR
Definition: rs.h:44
static std::vector< std::shared_ptr< device_info > > pick_l500_devices(std::shared_ptr< context > ctx, platform::backend_device_group &group)
std::map< uint64_t, devices_changed_callback_ptr > _devices_changed_callbacks
Definition: context.h:148
static std::vector< std::shared_ptr< device_info > > pick_tm2_devices(std::shared_ptr< context > ctx, std::vector< platform::usb_device_info > &usb)
Definition: tm-info.cpp:42
std::vector< std::shared_ptr< stream_profile_interface > > stream_profiles
Definition: streaming.h:79
static std::vector< std::shared_ptr< device_info > > pick_uvc_devices(const std::shared_ptr< context > &ctx, const std::vector< platform::uvc_device_info > &uvc_devices)
Definition: context.cpp:180
typename ::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
Video stream intrinsics.
Definition: rs_types.h:58
uint64_t register_internal_device_callback(devices_changed_callback_ptr callback)
Definition: context.cpp:461
detail::group1< detail::group0 > group()
Definition: group.hpp:472
void set_devices_changed_callback(devices_changed_callback_ptr callback)
Definition: context.cpp:486
std::shared_ptr< platform::backend > _backend
Definition: context.h:144
std::shared_ptr< rs2_devices_changed_callback > devices_changed_callback_ptr
Definition: src/types.h:884
int i
static uint64_t generate_id()
Definition: src/types.h:334
std::shared_ptr< device_interface > create(std::shared_ptr< context >, bool) const override
Definition: context.cpp:136
struct rs2_device_list rs2_device_list
Definition: rs_types.h:267
constexpr auto rs2_api_version
Definition: context.cpp:45
static std::vector< std::shared_ptr< device_info > > pick_recovery_devices(std::shared_ptr< context > ctx, const std::vector< platform::usb_device_info > &usb_devices)
Definition: context.cpp:147
std::vector< platform::uvc_device_info > filter_by_mi(const std::vector< platform::uvc_device_info > &devices, uint32_t mi)
Definition: context.cpp:663
std::vector< uvc_device_info > uvc_devices
Definition: backend.h:533
static std::vector< std::shared_ptr< device_info > > pick_sr300_devices(std::shared_ptr< context > ctx, std::vector< platform::uvc_device_info > &platform, std::vector< platform::usb_device_info > &usb)
Definition: sr300.cpp:69
const std::map< uint32_t, rs2_stream > platform_color_fourcc_to_rs2_stream
Definition: context.cpp:92
#define RS2_PRODUCT_LINE_SR300
Definition: rs_context.h:95
std::shared_ptr< stream_interface > _default_stream
Definition: context.cpp:236
void unregister_internal_device_callback(uint64_t cb_id)
Definition: context.cpp:475
GeneratorWrapper< T > map(Func &&function, GeneratorWrapper< U > &&generator)
Definition: catch.hpp:4271
devices_changed_callback_ptr _devices_changed_callback
Definition: context.h:150
const std::map< uint32_t, rs2_format > platform_color_fourcc_to_rs2_format
Definition: context.cpp:87
void copy(void *dst, void const *src, size_t size)
Definition: types.cpp:255
bool mi_present(const std::vector< platform::uvc_device_info > &devices, uint32_t mi)
Definition: context.cpp:643
std::shared_ptr< playback_device_info > add_device(const std::string &file)
Definition: context.cpp:552
std::string to_string(T value)


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