d400-device.cpp
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2016 Intel Corporation. All Rights Reserved.
3 
5 #include <src/device.h>
6 #include <src/image.h>
7 #include <src/metadata-parser.h>
8 #include <src/metadata.h>
9 #include <src/backend.h>
10 
11 #include "d400-device.h"
12 #include "d400-private.h"
13 #include "d400-options.h"
14 #include "d400-info.h"
15 #include "ds/ds-timestamp.h"
16 #include <src/stream.h>
17 #include <src/environment.h>
18 #include <src/depth-sensor.h>
19 #include "d400-color.h"
20 #include "d400-nonmonochrome.h"
22 #include <src/fourcc.h>
23 
28 
30 #include <src/proc/y8i-to-y8y8.h>
34 
35 #include <src/hdr-config.h>
36 #include "d400-thermal-monitor.h"
39 
40 #include <rsutils/string/hexdump.h>
41 #include <regex>
42 #include <iterator>
43 
46 
47 #ifdef HWM_OVER_XU
48 constexpr bool hw_mon_over_xu = true;
49 #else
50 constexpr bool hw_mon_over_xu = false;
51 #endif
52 
53 namespace librealsense
54 {
55  std::map<uint32_t, rs2_format> d400_depth_fourcc_to_rs2_format = {
56  {rs_fourcc('Y','U','Y','2'), RS2_FORMAT_YUYV},
57  {rs_fourcc('Y','U','Y','V'), RS2_FORMAT_YUYV},
58  {rs_fourcc('U','Y','V','Y'), RS2_FORMAT_UYVY},
59  {rs_fourcc('G','R','E','Y'), RS2_FORMAT_Y8},
60  {rs_fourcc('Y','8','I',' '), RS2_FORMAT_Y8I},
61  {rs_fourcc('W','1','0',' '), RS2_FORMAT_W10},
62  {rs_fourcc('Y','1','6',' '), RS2_FORMAT_Y16},
63  {rs_fourcc('Y','1','2','I'), RS2_FORMAT_Y12I},
64  {rs_fourcc('Z','1','6',' '), RS2_FORMAT_Z16},
65  {rs_fourcc('Z','1','6','H'), RS2_FORMAT_Z16H},
66  {rs_fourcc('R','G','B','2'), RS2_FORMAT_BGR8},
67  {rs_fourcc('M','J','P','G'), RS2_FORMAT_MJPEG},
68  {rs_fourcc('B','Y','R','2'), RS2_FORMAT_RAW16}
69 
70  };
71  std::map<uint32_t, rs2_stream> d400_depth_fourcc_to_rs2_stream = {
72  {rs_fourcc('Y','U','Y','2'), RS2_STREAM_COLOR},
73  {rs_fourcc('Y','U','Y','V'), RS2_STREAM_COLOR},
74  {rs_fourcc('U','Y','V','Y'), RS2_STREAM_INFRARED},
75  {rs_fourcc('G','R','E','Y'), RS2_STREAM_INFRARED},
76  {rs_fourcc('Y','8','I',' '), RS2_STREAM_INFRARED},
77  {rs_fourcc('W','1','0',' '), RS2_STREAM_INFRARED},
78  {rs_fourcc('Y','1','6',' '), RS2_STREAM_INFRARED},
79  {rs_fourcc('Y','1','2','I'), RS2_STREAM_INFRARED},
80  {rs_fourcc('R','G','B','2'), RS2_STREAM_INFRARED},
81  {rs_fourcc('Z','1','6',' '), RS2_STREAM_DEPTH},
82  {rs_fourcc('Z','1','6','H'), RS2_STREAM_DEPTH},
83  {rs_fourcc('B','Y','R','2'), RS2_STREAM_COLOR},
84  {rs_fourcc('M','J','P','G'), RS2_STREAM_COLOR}
85  };
86 
87  std::vector<uint8_t> d400_device::send_receive_raw_data(const std::vector<uint8_t>& input)
88  {
89  return _hw_monitor->send(input);
90  }
91 
97  uint8_t const * data,
98  size_t dataLength) const
99  {
100  return _hw_monitor->build_command(opcode, param1, param2, param3, param4, data, dataLength);
101  }
102 
104  {
106  cmd.require_response = false;
107  _hw_monitor->send(cmd);
108  }
109 
111  {
112  _ds_device_common->enter_update_state();
113  }
114 
116  {
117  return _ds_device_common->backup_flash(callback);
118  }
119 
120  void d400_device::update_flash(const std::vector<uint8_t>& image, rs2_update_progress_callback_sptr callback, int update_mode)
121  {
122  _ds_device_common->update_flash(image, callback, update_mode);
123  }
124 
125  bool d400_device::check_fw_compatibility( const std::vector< uint8_t > & image ) const
126  {
127  // check if the given FW size matches the expected FW size
128  if( ( image.size() != signed_fw_size ) )
130  rsutils::string::from() << "Unsupported firmware binary image provided - " << image.size() << " bytes" );
131 
133 
136  {
139  << "Min and Max firmware versions have not been defined for this device: "
140  << std::hex << _pid );
141  }
142  bool result = ( firmware_version( fw_version ) >= firmware_version( it->second ) );
143  if( ! result )
144  LOG_ERROR( "Firmware version isn't compatible" << fw_version );
145 
146  return result;
147  }
148 
150  : public synthetic_sensor
151  , public video_sensor_interface
152  , public depth_stereo_sensor
153  , public roi_sensor_base
154  {
155  public:
157  std::shared_ptr<uvc_sensor> uvc_sensor)
160  _owner(owner),
161  _depth_units(-1),
162  _hdr_cfg(nullptr)
163  { }
164 
166  {
168  };
169 
171  {
173 
176  {
177  return result;
178  }
179  else
180  {
185  }
186  }
187 
188  void set_frame_metadata_modifier(on_frame_md callback) override
189  {
190  _metadata_modifier = callback;
191  auto s = get_raw_sensor().get();
192  auto uvc = As< librealsense::uvc_sensor >(s);
193  if(uvc)
194  uvc->set_frame_metadata_modifier(callback);
195  }
196 
197  void open(const stream_profiles& requests) override
198  {
199  group_multiple_fw_calls(*this, [&]() {
202 
203  synthetic_sensor::open(requests);
204 
205  // Activate Thermal Compensation tracking
207  _owner->_thermal_monitor->update(true);
208  }); //group_multiple_fw_calls
209  }
210 
211  void close() override
212  {
213  // Deactivate Thermal Compensation tracking
215  _owner->_thermal_monitor->update(false);
216 
218  }
219 
221  {
226  }
227 
228  /*
229  Infrared profiles are initialized with the following logic:
230  - If device has color sensor (D415 / D435), infrared profile is chosen with Y8 format
231  - If device does not have color sensor:
232  * if it is a rolling shutter device (D400 / D410 / D415 / D405), infrared profile is chosen with RGB8 format
233  * for other devices (D420 / D430), infrared profile is chosen with Y8 format
234  */
236  {
238 
239  auto&& results = synthetic_sensor::init_stream_profiles();
240 
241  for (auto&& p : results)
242  {
243  // Register stream types
244  if (p->get_stream_type() == RS2_STREAM_DEPTH)
245  {
247  }
248  else if (p->get_stream_type() == RS2_STREAM_INFRARED && p->get_stream_index() < 2)
249  {
251  }
252  else if (p->get_stream_type() == RS2_STREAM_INFRARED && p->get_stream_index() == 2)
253  {
255  }
256  else if (p->get_stream_type() == RS2_STREAM_COLOR)
257  {
259  }
260  auto&& vid_profile = dynamic_cast<video_stream_profile_interface*>(p.get());
261 
262  // used when color stream comes from depth sensor (as in D405)
263  if (p->get_stream_type() == RS2_STREAM_COLOR)
264  {
265  const auto&& profile = to_profile(p.get());
266  std::weak_ptr<d400_depth_sensor> wp =
267  std::dynamic_pointer_cast<d400_depth_sensor>(this->shared_from_this());
268  vid_profile->set_intrinsics([profile, wp]()
269  {
270  auto sp = wp.lock();
271  if (sp)
272  return sp->get_color_intrinsics(profile);
273  else
274  return rs2_intrinsics{};
275  });
276  }
277  // Register intrinsics
278  else if (p->get_format() != RS2_FORMAT_Y16) // Y16 format indicate unrectified images, no intrinsics are available for these
279  {
280  const auto&& profile = to_profile(p.get());
281  std::weak_ptr<d400_depth_sensor> wp =
282  std::dynamic_pointer_cast<d400_depth_sensor>(this->shared_from_this());
283  vid_profile->set_intrinsics([profile, wp]()
284  {
285  auto sp = wp.lock();
286  if (sp)
287  return sp->get_intrinsics(profile);
288  else
289  return rs2_intrinsics{};
290  });
291  }
292  }
293 
294  return results;
295  }
296 
297  float get_depth_scale() const override
298  {
299  if (_depth_units < 0)
301  return _depth_units;
302  }
303 
304  void set_depth_scale(float val)
305  {
306  _depth_units = val;
308  }
309 
311  {
312  _hdr_cfg = std::make_shared<hdr_config>(*(_owner->_hw_monitor), get_raw_sensor(),
314  }
315 
316  std::shared_ptr<hdr_config> get_hdr_config() { return _hdr_cfg; }
317 
318  float get_stereo_baseline_mm() const override { return _owner->get_stereo_baseline_mm(); }
319 
320  float get_preset_max_value() const override
321  {
322  float preset_max_value = RS2_RS400_VISUAL_PRESET_COUNT - 1;
323  switch (_owner->_pid)
324  {
325  case ds::RS400_PID:
326  case ds::RS410_PID:
327  case ds::RS415_PID:
328  case ds::RS460_PID:
329  preset_max_value = static_cast<float>(RS2_RS400_VISUAL_PRESET_REMOVE_IR_PATTERN);
330  break;
331  default:
332  preset_max_value = static_cast<float>(RS2_RS400_VISUAL_PRESET_MEDIUM_DENSITY);
333  }
334  return preset_max_value;
335  }
336 
337  protected:
339  mutable std::atomic<float> _depth_units;
341  std::shared_ptr<hdr_config> _hdr_cfg;
342  };
343 
345  {
346  public:
348  std::shared_ptr<uvc_sensor> uvc_sensor)
349  : d400_depth_sensor(owner, uvc_sensor), _owner(owner)
350  {}
351 
353  {
355 
356  auto&& results = synthetic_sensor::init_stream_profiles();
357 
358  for (auto&& p : results)
359  {
360  // Register stream types
361  if (p->get_stream_type() == RS2_STREAM_DEPTH)
362  {
364  }
365  else if (p->get_stream_type() == RS2_STREAM_INFRARED && p->get_stream_index() < 2)
366  {
368  }
369  else if (p->get_stream_type() == RS2_STREAM_INFRARED && p->get_stream_index() == 2)
370  {
372  }
373  else if (p->get_stream_type() == RS2_STREAM_COLOR)
374  {
376  }
377  auto&& video = dynamic_cast<video_stream_profile_interface*>(p.get());
378 
379  // Register intrinsics
380  if (p->get_format() != RS2_FORMAT_Y16) // Y16 format indicate unrectified images, no intrinsics are available for these
381  {
382  const auto&& profile = to_profile(p.get());
383  std::weak_ptr<d400_depth_sensor> wp = std::dynamic_pointer_cast<d400_depth_sensor>(this->shared_from_this());
384  video->set_intrinsics([profile, wp]()
385  {
386  auto sp = wp.lock();
387  if (sp)
388  return sp->get_intrinsics(profile);
389  else
390  return rs2_intrinsics{};
391  });
392  }
393  }
394 
395  return results;
396  }
397 
398  private:
400  };
401 
403  {
404  return _ds_device_common->is_camera_in_advanced_mode();
405  }
406 
408  {
409  using namespace ds;
410  auto table = check_calib<d400_coefficients_table>(*_coefficients_table_raw);
411  return fabs(table->baseline);
412  }
413 
415  {
416  command cmd(ds::GETINTCAL, static_cast<int>(table_id));
417  return _hw_monitor->send(cmd);
418  }
419 
420  std::vector<uint8_t> d400_device::get_new_calibration_table() const
421  {
422  if (_fw_version >= firmware_version("5.11.9.5"))
423  {
425  return _hw_monitor->send(cmd);
426  }
427  return {};
428  }
429 
430  ds::ds_caps d400_device::parse_device_capabilities( const std::vector<uint8_t> &gvd_buf ) const
431  {
432  using namespace ds;
433 
434  // Opaque retrieval
435  ds_caps val{ds_caps::CAP_UNDEFINED};
436  if (gvd_buf[active_projector]) // DepthActiveMode
437  val |= ds_caps::CAP_ACTIVE_PROJECTOR;
438  if (gvd_buf[rgb_sensor]) // WithRGB
439  val |= ds_caps::CAP_RGB_SENSOR;
440  if (gvd_buf[imu_sensor])
441  {
442  val |= ds_caps::CAP_IMU_SENSOR;
443  if (gvd_buf[imu_acc_chip_id] == I2C_IMU_BMI055_ID_ACC)
444  val |= ds_caps::CAP_BMI_055;
445  else if (gvd_buf[imu_acc_chip_id] == I2C_IMU_BMI085_ID_ACC)
446  val |= ds_caps::CAP_BMI_085;
447  else if (d400_hid_bmi_055_pid.end() != d400_hid_bmi_055_pid.find(_pid))
448  val |= ds_caps::CAP_BMI_055;
449  else if (d400_hid_bmi_085_pid.end() != d400_hid_bmi_085_pid.find(_pid))
450  val |= ds_caps::CAP_BMI_085;
451  else
452  LOG_WARNING("The IMU sensor is undefined for PID " << std::hex << _pid << " and imu_chip_id: " << gvd_buf[imu_acc_chip_id] << std::dec);
453  }
454  if (0xFF != (gvd_buf[fisheye_sensor_lb] & gvd_buf[fisheye_sensor_hb]))
455  val |= ds_caps::CAP_FISHEYE_SENSOR;
456  if (0x1 == gvd_buf[depth_sensor_type])
457  val |= ds_caps::CAP_ROLLING_SHUTTER; // e.g. ASRC
458  if (0x2 == gvd_buf[depth_sensor_type])
459  val |= ds_caps::CAP_GLOBAL_SHUTTER; // e.g. AWGC
460  // Option INTER_CAM_SYNC_MODE is not enabled in D405
461  if (_pid != ds::RS405_PID)
462  val |= ds_caps::CAP_INTERCAM_HW_SYNC;
463  if (gvd_buf[ip65_sealed_offset] == 0x1)
464  val |= ds_caps::CAP_IP65;
465  if (gvd_buf[ir_filter_offset] == 0x1)
466  val |= ds_caps::CAP_IR_FILTER;
467  return val;
468  }
469 
470  std::shared_ptr<synthetic_sensor> d400_device::create_depth_device(std::shared_ptr<context> ctx,
471  const std::vector<platform::uvc_device_info>& all_device_infos)
472  {
473  using namespace ds;
474 
475  std::vector<std::shared_ptr<platform::uvc_device>> depth_devices;
476  for (auto&& info : filter_by_mi(all_device_infos, 0)) // Filter just mi=0, DEPTH
477  depth_devices.push_back( get_backend()->create_uvc_device( info ) );
478 
479  std::unique_ptr< frame_timestamp_reader > timestamp_reader_backup( new ds_timestamp_reader() );
480  frame_timestamp_reader* timestamp_reader_from_metadata;
481  if (all_device_infos.front().pid != RS457_PID)
482  timestamp_reader_from_metadata = new ds_timestamp_reader_from_metadata(std::move(timestamp_reader_backup));
483  else
484  timestamp_reader_from_metadata = new ds_timestamp_reader_from_metadata_mipi(std::move(timestamp_reader_backup));
485 
486  std::unique_ptr<frame_timestamp_reader> timestamp_reader_metadata(timestamp_reader_from_metadata);
487  auto enable_global_time_option = std::shared_ptr<global_time_option>(new global_time_option());
488 
489  auto raw_depth_ep = std::make_shared<uvc_sensor>("Raw Depth Sensor", std::make_shared<platform::multi_pins_uvc_device>(depth_devices),
490  std::unique_ptr<frame_timestamp_reader>(new global_timestamp_reader(std::move(timestamp_reader_metadata), _tf_keeper, enable_global_time_option)), this);
491 
492  raw_depth_ep->register_xu(depth_xu); // make sure the XU is initialized every time we power the camera
493 
494  auto depth_ep = std::make_shared<d400_depth_sensor>(this, raw_depth_ep);
495 
496  depth_ep->register_info(RS2_CAMERA_INFO_PHYSICAL_PORT, filter_by_mi(all_device_infos, 0).front().device_path);
497 
498  depth_ep->register_option(RS2_OPTION_GLOBAL_TIME_ENABLED, enable_global_time_option);
499 
500  depth_ep->register_processing_block(processing_block_factory::create_id_pbf(RS2_FORMAT_Y8, RS2_STREAM_INFRARED, 1));
501  depth_ep->register_processing_block(processing_block_factory::create_id_pbf(RS2_FORMAT_Z16, RS2_STREAM_DEPTH));
502 
503  depth_ep->register_processing_block({ {RS2_FORMAT_W10} }, { {RS2_FORMAT_RAW10, RS2_STREAM_INFRARED, 1} }, []() { return std::make_shared<w10_converter>(RS2_FORMAT_RAW10); });
504  depth_ep->register_processing_block({ {RS2_FORMAT_W10} }, { {RS2_FORMAT_Y10BPACK, RS2_STREAM_INFRARED, 1} }, []() { return std::make_shared<w10_converter>(RS2_FORMAT_Y10BPACK); });
505 
506  return depth_ep;
507  }
508 
509  d400_device::d400_device( std::shared_ptr< const d400_info > const & dev_info )
510  : backend_device(dev_info), global_time_interface(),
511  auto_calibrated(),
516  _color_stream(nullptr)
517  {
518  _depth_device_idx = add_sensor( create_depth_device( dev_info->get_context(), dev_info->get_group().uvc_devices ) );
519  init( dev_info->get_context(), dev_info->get_group() );
520  }
521 
522  void d400_device::init(std::shared_ptr<context> ctx,
523  const platform::backend_device_group& group)
524  {
525  using namespace ds;
526 
527  auto raw_sensor = get_raw_depth_sensor();
528  _pid = group.uvc_devices.front().pid;
529  // to be changed for D457
530  bool mipi_sensor = (RS457_PID == _pid);
531 
532  _color_calib_table_raw = [this]()
533  {
534  return get_d400_raw_calibration_table(d400_calibration_table_id::rgb_calibration_id);
535  };
536 
537  if (((hw_mon_over_xu) && (RS400_IMU_PID != _pid)) || (!group.usb_devices.size()))
538  {
539  _hw_monitor = std::make_shared<hw_monitor>(
540  std::make_shared<locked_transfer>(
541  std::make_shared<command_transfer_over_xu>( *raw_sensor, depth_xu, DS5_HWMONITOR ),
542  raw_sensor ) );
543  }
544  else
545  {
546  if( ! mipi_sensor )
547  _hw_monitor = std::make_shared< hw_monitor >(
548  std::make_shared< locked_transfer >(
549  get_backend()->create_usb_device( group.usb_devices.front() ),
550  raw_sensor ) );
551  }
553 
554  _ds_device_common = std::make_shared<ds_device_common>(this, _hw_monitor);
555 
556  // Define Left-to-Right extrinsics calculation (lazy)
557  // Reference CS - Right-handed; positive [X,Y,Z] point to [Left,Up,Forward] accordingly.
558  _left_right_extrinsics = std::make_shared< rsutils::lazy< rs2_extrinsics > >(
559  [this]()
560  {
562  auto table = check_calib<d400_coefficients_table>(*_coefficients_table_raw);
563  ext.translation[0] = 0.001f * table->baseline; // mm to meters
564  return ext;
565  });
566 
569 
573 
574  _coefficients_table_raw = [this]() { return get_d400_raw_calibration_table(d400_calibration_table_id::coefficients_table_id); };
575  _new_calib_table_raw = [this]() { return get_new_calibration_table(); };
576 
578 
579  std::vector<uint8_t> gvd_buff(HW_MONITOR_BUFFER_SIZE);
580 
581  auto& depth_sensor = get_depth_sensor();
582  auto raw_depth_sensor = get_raw_depth_sensor();
583 
584  using namespace platform;
585 
586  // minimal firmware version in which hdr feature is supported
587  firmware_version hdr_firmware_version("5.12.8.100");
588 
589  std::string optic_serial, asic_serial, pid_hex_str, usb_type_str;
590  bool advanced_mode, usb_modality;
592 
593  _hw_monitor->get_gvd(gvd_buff.size(), gvd_buff.data(), GVD);
594 
595  std::string fwv;
596  _ds_device_common->get_fw_details( gvd_buff, optic_serial, asic_serial, fwv );
597 
599 
601  if (_fw_version >= firmware_version("5.10.4.0"))
603 
604  //D457 Development
605  advanced_mode = is_camera_in_advanced_mode();
606  auto _usb_mode = usb3_type;
607  usb_type_str = usb_spec_names.at(_usb_mode);
608  usb_modality = (_fw_version >= firmware_version("5.9.8.0"));
609  if (usb_modality)
610  {
611  _usb_mode = raw_depth_sensor->get_usb_specification();
612  if (usb_spec_names.count(_usb_mode) && (usb_undefined != _usb_mode))
613  usb_type_str = usb_spec_names.at(_usb_mode);
614  else // Backend fails to provide USB descriptor - occurs with RS3 build. Requires further work
615  usb_modality = false;
616  }
617 
618  if (_fw_version >= firmware_version("5.12.1.1"))
619  {
621  }
622 
623  depth_sensor.register_processing_block(
624  { {RS2_FORMAT_Y8I} },
626  []() { return std::make_shared<y8i_to_y8y8>(); }
627  ); // L+R
628 
629  if (!mipi_sensor)
630  {
631  depth_sensor.register_processing_block(
632  { RS2_FORMAT_Y12I },
634  []() {return std::make_shared<y12i_to_y16y16>(); }
635  );
636  }
637  else
638  {
639  depth_sensor.register_processing_block(
640  { RS2_FORMAT_Y12I },
642  []() {return std::make_shared<y12i_to_y16y16_mipi>(); }
643  );
644  }
645 
646 
647  pid_hex_str = rsutils::string::from() << std::uppercase << rsutils::string::hexdump( _pid );
648 
649  if ((_pid == RS416_PID || _pid == RS416_RGB_PID) && _fw_version >= firmware_version("5.12.0.1"))
650  {
652  std::make_shared<uvc_xu_option<uint8_t>>( raw_depth_sensor, depth_xu, DS5_HARDWARE_PRESET,
653  "Hardware pipe configuration" ) );
654  depth_sensor.register_option(RS2_OPTION_LED_POWER,
655  std::make_shared<uvc_xu_option<uint16_t>>( raw_depth_sensor, depth_xu, DS5_LED_PWR,
656  "Set the power level of the LED, with 0 meaning LED off"));
657  }
658 
659  if (_fw_version >= firmware_version("5.6.3.0"))
660  {
661  _is_locked = _ds_device_common->is_locked( gvd_buff.data(), is_camera_locked_offset );
662  }
663 
664  if (_fw_version >= firmware_version("5.5.8.0"))
665  //if hw_monitor was created by usb replace it with xu
666  // D400_IMU will remain using USB interface due to HW limitations
667  {
668  if (_pid == ds::RS457_PID)
669  {
671  std::make_shared<asic_temperature_option_mipi>(_hw_monitor,
673  }
674  else
675  {
677  std::make_shared<uvc_xu_option<uint8_t>>( raw_depth_sensor, depth_xu, DS5_EXT_TRIGGER,
678  "Generate trigger from the camera to external device once per frame"));
679 
681  std::make_shared< asic_and_projector_temperature_options >( raw_depth_sensor,
683 
684  // D457 dev - get_xu fails for D457 - error polling id not defined
685  auto error_control = std::make_shared<uvc_xu_option<uint8_t>>( raw_depth_sensor, depth_xu,
686  DS5_ERROR_REPORTING, "Error reporting");
687 
688  _polling_error_handler = std::make_shared<polling_error_handler>(1000,
689  error_control,
690  raw_depth_sensor->get_notifications_processor(),
691  std::make_shared< ds_notification_decoder >( d400_fw_error_report ) );
692 
693  depth_sensor.register_option(RS2_OPTION_ERROR_POLLING_ENABLED, std::make_shared<polling_errors_disable>(_polling_error_handler));
694  }
695  }
696 
697  if ((val_in_range(_pid, { RS455_PID })) && (_fw_version >= firmware_version("5.12.11.0")))
698  {
699  auto thermal_compensation_toggle = std::make_shared<protected_xu_option<uint8_t>>( raw_depth_sensor, depth_xu,
700  ds::DS5_THERMAL_COMPENSATION, "Toggle Thermal Compensation Mechanism");
701 
702  auto temperature_sensor = depth_sensor.get_option_handler(RS2_OPTION_ASIC_TEMPERATURE);
703 
704  _thermal_monitor = std::make_shared<d400_thermal_monitor>(temperature_sensor, thermal_compensation_toggle);
705 
707  std::make_shared<thermal_compensation>(_thermal_monitor,thermal_compensation_toggle));
708  }
709 
710  auto ir_filter_mask = ds_caps::CAP_IR_FILTER;
712  (_device_capabilities & ir_filter_mask) == ir_filter_mask &&
713  is_capability_supports(ds_caps::CAP_IR_FILTER, gvd_buff[gvd_version_offset]))
714  {
715  update_device_name(device_name, ds_caps::CAP_IR_FILTER);
716  }
717 
718  auto ip65_mask = ds_caps::CAP_IP65;
719  if (val_in_range(_pid, { RS455_PID })&&
720  (_device_capabilities & ip65_mask) == ip65_mask &&
721  is_capability_supports(ds_caps::CAP_IP65, gvd_buff[gvd_version_offset]))
722  {
723  update_device_name(device_name, ds_caps::CAP_IP65);
724  }
725 
726  std::shared_ptr<option> exposure_option = nullptr;
727  std::shared_ptr<option> gain_option = nullptr;
728  std::shared_ptr<hdr_option> hdr_enabled_option = nullptr;
729 
730  //EXPOSURE AND GAIN - preparing uvc options
731  auto uvc_xu_exposure_option = std::make_shared<uvc_xu_option<uint32_t>>( raw_depth_sensor,
732  depth_xu,
733  DS5_EXPOSURE,
734  "Depth Exposure (usec)");
735  option_range exposure_range = uvc_xu_exposure_option->get_range();
736  auto uvc_pu_gain_option = std::make_shared<uvc_pu_option>( raw_depth_sensor, RS2_OPTION_GAIN);
737  option_range gain_range = uvc_pu_gain_option->get_range();
738 
739  //AUTO EXPOSURE
740  auto enable_auto_exposure = std::make_shared<uvc_xu_option<uint8_t>>( raw_depth_sensor,
741  depth_xu,
743  "Enable Auto Exposure");
744  depth_sensor.register_option(RS2_OPTION_ENABLE_AUTO_EXPOSURE, enable_auto_exposure);
745 
746  // register HDR options
747  if (_fw_version >= hdr_firmware_version)
748  {
749  auto d400_depth = As<d400_depth_sensor, synthetic_sensor>(&get_depth_sensor());
750  d400_depth->init_hdr_config(exposure_range, gain_range);
751  auto&& hdr_cfg = d400_depth->get_hdr_config();
752 
753  // values from 4 to 14 - for internal use
754  // value 15 - saved for emiter on off subpreset
755  option_range hdr_id_range = { 0.f /*min*/, 3.f /*max*/, 1.f /*step*/, 1.f /*default*/ };
756  auto hdr_id_option = std::make_shared<hdr_option>(hdr_cfg, RS2_OPTION_SEQUENCE_NAME, hdr_id_range,
757  std::map<float, std::string>{ {0.f, "0"}, { 1.f, "1" }, { 2.f, "2" }, { 3.f, "3" } });
758  depth_sensor.register_option(RS2_OPTION_SEQUENCE_NAME, hdr_id_option);
759 
760  option_range hdr_sequence_size_range = { 2.f /*min*/, 2.f /*max*/, 1.f /*step*/, 2.f /*default*/ };
761  auto hdr_sequence_size_option = std::make_shared<hdr_option>(hdr_cfg, RS2_OPTION_SEQUENCE_SIZE, hdr_sequence_size_range,
762  std::map<float, std::string>{ { 2.f, "2" } });
763  depth_sensor.register_option(RS2_OPTION_SEQUENCE_SIZE, hdr_sequence_size_option);
764 
765  option_range hdr_sequ_id_range = { 0.f /*min*/, 2.f /*max*/, 1.f /*step*/, 0.f /*default*/ };
766  auto hdr_sequ_id_option = std::make_shared<hdr_option>(hdr_cfg, RS2_OPTION_SEQUENCE_ID, hdr_sequ_id_range,
767  std::map<float, std::string>{ {0.f, "UVC"}, { 1.f, "1" }, { 2.f, "2" } });
768  depth_sensor.register_option(RS2_OPTION_SEQUENCE_ID, hdr_sequ_id_option);
769 
770  option_range hdr_enable_range = { 0.f /*min*/, 1.f /*max*/, 1.f /*step*/, 0.f /*default*/ };
771  hdr_enabled_option = std::make_shared<hdr_option>(hdr_cfg, RS2_OPTION_HDR_ENABLED, hdr_enable_range);
772  depth_sensor.register_option(RS2_OPTION_HDR_ENABLED, hdr_enabled_option);
773 
774  //EXPOSURE AND GAIN - preparing hdr options
775  auto hdr_exposure_option = std::make_shared<hdr_option>(hdr_cfg, RS2_OPTION_EXPOSURE, exposure_range);
776  auto hdr_gain_option = std::make_shared<hdr_option>(hdr_cfg, RS2_OPTION_GAIN, gain_range);
777 
778  //EXPOSURE AND GAIN - preparing hybrid options
779  auto hdr_conditional_exposure_option = std::make_shared<hdr_conditional_option>(hdr_cfg, uvc_xu_exposure_option, hdr_exposure_option);
780  auto hdr_conditional_gain_option = std::make_shared<hdr_conditional_option>(hdr_cfg, uvc_pu_gain_option, hdr_gain_option);
781 
782  exposure_option = hdr_conditional_exposure_option;
783  gain_option = hdr_conditional_gain_option;
784 
785  std::vector<std::pair<std::shared_ptr<option>, std::string>> options_and_reasons = { std::make_pair(hdr_enabled_option,
786  "Auto Exposure cannot be set while HDR is enabled") };
788  std::make_shared<gated_option>(
789  enable_auto_exposure,
790  options_and_reasons));
791  }
792  else
793  {
794  exposure_option = uvc_xu_exposure_option;
795  gain_option = uvc_pu_gain_option;
796  }
797 
798  // DEPTH AUTO EXPOSURE MODE
799  if ((val_in_range(_pid, { RS455_PID })) && (_fw_version >= firmware_version("5.15.0.0")))
800  {
801  auto depth_auto_exposure_mode = std::make_shared<uvc_xu_option<uint8_t>>( raw_depth_sensor,
802  depth_xu,
804  "Depth Auto Exposure Mode",
805  std::map<float, std::string>{
806  { (float)RS2_DEPTH_AUTO_EXPOSURE_REGULAR, "Regular" },
807  { (float)RS2_DEPTH_AUTO_EXPOSURE_ACCELERATED, "Accelerated" } } , false);
808 
809  depth_sensor.register_option(
810  RS2_OPTION_DEPTH_AUTO_EXPOSURE_MODE, depth_auto_exposure_mode );
811  }
812 
813  //EXPOSURE
814  depth_sensor.register_option(RS2_OPTION_EXPOSURE,
815  std::make_shared<auto_disabling_control>(
816  exposure_option,
817  enable_auto_exposure));
818 
819  //GAIN
820  depth_sensor.register_option(RS2_OPTION_GAIN,
821  std::make_shared<auto_disabling_control>(
822  gain_option,
823  enable_auto_exposure));
824 
825  // Alternating laser pattern is applicable for global shutter/active SKUs
826  auto mask = ds_caps::CAP_GLOBAL_SHUTTER | ds_caps::CAP_ACTIVE_PROJECTOR;
827  // Alternating laser pattern should be set and query in a different way according to the firmware version
828  if ((_fw_version >= firmware_version("5.11.3.0")) && ((_device_capabilities & mask) == mask))
829  {
830  bool is_fw_version_using_id = (_fw_version >= firmware_version("5.12.8.100"));
831  auto alternating_emitter_opt = std::make_shared<alternating_emitter_option>(*_hw_monitor, is_fw_version_using_id);
832  auto emitter_always_on_opt = std::make_shared<emitter_always_on_option>( _hw_monitor, ds::LASERONCONST, ds::LASERONCONST );
833 
834  if ((_fw_version >= firmware_version("5.12.1.0")) && ((_device_capabilities & ds_caps::CAP_GLOBAL_SHUTTER) == ds_caps::CAP_GLOBAL_SHUTTER))
835  {
836  std::vector<std::pair<std::shared_ptr<option>, std::string>> options_and_reasons = { std::make_pair(alternating_emitter_opt,
837  "Emitter always ON cannot be set while Emitter ON/OFF is enabled") };
839  std::make_shared<gated_option>(
840  emitter_always_on_opt,
841  options_and_reasons));
842  }
843 
844  if (_fw_version >= hdr_firmware_version)
845  {
846  std::vector<std::pair<std::shared_ptr<option>, std::string>> options_and_reasons = { std::make_pair(hdr_enabled_option, "Emitter ON/OFF cannot be set while HDR is enabled"),
847  std::make_pair(emitter_always_on_opt, "Emitter ON/OFF cannot be set while Emitter always ON is enabled") };
848  depth_sensor.register_option(RS2_OPTION_EMITTER_ON_OFF,
849  std::make_shared<gated_option>(
850  alternating_emitter_opt,
851  options_and_reasons
852  ));
853  }
854  else if ((_fw_version >= firmware_version("5.12.1.0")) && ((_device_capabilities & ds_caps::CAP_GLOBAL_SHUTTER) == ds_caps::CAP_GLOBAL_SHUTTER))
855  {
856  std::vector<std::pair<std::shared_ptr<option>, std::string>> options_and_reasons = { std::make_pair(emitter_always_on_opt,
857  "Emitter ON/OFF cannot be set while Emitter always ON is enabled") };
858  depth_sensor.register_option(RS2_OPTION_EMITTER_ON_OFF,
859  std::make_shared<gated_option>(
860  alternating_emitter_opt,
861  options_and_reasons));
862  }
863  else
864  {
865  depth_sensor.register_option(RS2_OPTION_EMITTER_ON_OFF, alternating_emitter_opt);
866  }
867 
868  }
869 
870  if ((_device_capabilities & ds_caps::CAP_INTERCAM_HW_SYNC) == ds_caps::CAP_INTERCAM_HW_SYNC)
871  {
872  if (_fw_version >= firmware_version("5.12.12.100") && (_device_capabilities & ds_caps::CAP_GLOBAL_SHUTTER) == ds_caps::CAP_GLOBAL_SHUTTER)
873  {
875  std::make_shared<external_sync_mode>(*_hw_monitor, raw_depth_sensor, 3));
876  }
877  else if (_fw_version >= firmware_version("5.12.4.0") && (_device_capabilities & ds_caps::CAP_GLOBAL_SHUTTER) == ds_caps::CAP_GLOBAL_SHUTTER)
878  {
880  std::make_shared<external_sync_mode>(*_hw_monitor, raw_depth_sensor, 2));
881  }
882  else if (_fw_version >= firmware_version("5.9.15.1"))
883  {
885  std::make_shared<external_sync_mode>(*_hw_monitor, raw_depth_sensor, 1));
886  }
887  }
888 
889  if (!val_in_range(_pid, { ds::RS457_PID }))
890  {
891  depth_sensor.register_option( RS2_OPTION_STEREO_BASELINE,
892  std::make_shared< const_value_option >(
893  "Distance in mm between the stereo imagers",
894  rsutils::lazy< float >( [this]() { return get_stereo_baseline_mm(); } ) ) );
895  }
896 
897  if (advanced_mode && _fw_version >= firmware_version("5.6.3.0"))
898  {
899  auto depth_scale = std::make_shared<depth_scale_option>(*_hw_monitor);
900  auto depth_sensor = As<d400_depth_sensor, synthetic_sensor>(&get_depth_sensor());
902 
903  depth_scale->add_observer([depth_sensor](float val)
904  {
905  depth_sensor->set_depth_scale(val);
906  });
907 
909  }
910  else
911  {
912  float default_depth_units = 0.001f; //meters
913  // default depth units is different for D405
914  if (_pid == RS405_PID)
915  default_depth_units = 0.0001f; //meters
916  depth_sensor.register_option(RS2_OPTION_DEPTH_UNITS, std::make_shared<const_value_option>("Number of meters represented by a single depth unit",
917  rsutils::lazy< float >( [default_depth_units]() { return default_depth_units; } ) ) );
918  }
919  }); //group_multiple_fw_calls
920 
921 
922  // REGISTER METADATA
923  if (!mipi_sensor)
924  {
925  register_metadata(depth_sensor, hdr_firmware_version);
926  }
927  else
928  {
929  // used for mipi device
930  register_metadata_mipi(depth_sensor, hdr_firmware_version);
931  }
932  //mipi
933 
939  register_info(RS2_CAMERA_INFO_PHYSICAL_PORT, group.uvc_devices.front().device_path);
941  register_info(RS2_CAMERA_INFO_ADVANCED_MODE, ((advanced_mode) ? "YES" : "NO"));
946  register_info(RS2_CAMERA_INFO_DFU_DEVICE_PATH, group.uvc_devices.front().dfu_device_path);
947 
948  if (usb_modality)
950 
951  std::string curr_version= _fw_version;
952 
954  }
955 
957  {
959  auto pid = get_pid();
960 
961  if( ( pid == ds::RS457_PID || pid == ds::RS455_PID ) && fw_ver >= firmware_version( 5, 14, 0, 0 ) )
962  register_feature( std::make_shared< emitter_frequency_feature >( get_depth_sensor() ) );
963 
964  if( fw_ver >= firmware_version( 5, 11, 9, 0 ) )
965  register_feature( std::make_shared< amplitude_factor_feature >() );
966 
967  if( fw_ver >= firmware_version( 5, 9, 10, 0 ) ) // TODO - add PID here? Now checked at advanced_mode
968  register_feature( std::make_shared< remove_ir_pattern_feature >() );
969 
970  register_feature( std::make_shared< auto_exposure_roi_feature >( get_depth_sensor(), _hw_monitor ) );
971 
972  if( pid != ds::RS457_PID && pid != ds::RS415_PID && fw_ver >= firmware_version( 5, 12, 10, 11 ) )
973  {
975  std::make_shared< auto_exposure_limit_feature >( get_depth_sensor(), d400_device::_hw_monitor ) );
976  register_feature( std::make_shared< gain_limit_feature >( get_depth_sensor(), d400_device::_hw_monitor ) );
977  }
978  }
979 
980  void d400_device::register_metadata(const synthetic_sensor &depth_sensor, const firmware_version& hdr_firmware_version) const
981  {
983 
984  // attributes of md_capture_timing
985  auto md_prop_offset = metadata_raw_mode_offset +
986  offsetof(md_depth_mode, depth_y_mode) +
987  offsetof(md_depth_y_normal_mode, intel_capture_timing);
988 
992 
993  // attributes of md_capture_stats
994  md_prop_offset = metadata_raw_mode_offset +
995  offsetof(md_depth_mode, depth_y_mode) +
996  offsetof(md_depth_y_normal_mode, intel_capture_stats);
997 
999 
1000  // attributes of md_depth_control
1001  md_prop_offset = metadata_raw_mode_offset +
1002  offsetof(md_depth_mode, depth_y_mode) +
1003  offsetof(md_depth_y_normal_mode, intel_depth_control);
1004 
1005 
1009 
1012  [](const rs2_metadata_type& param) { return param == 1 ? 1 : 0; })); // starting at version 2.30.1 this control is superceeded by RS2_FRAME_METADATA_FRAME_EMITTER_MODE
1020 
1021  // md_configuration - will be used for internal validation only
1022  md_prop_offset = metadata_raw_mode_offset + offsetof(md_depth_mode, depth_y_mode) + offsetof(md_depth_y_normal_mode, intel_configuration);
1023 
1029  depth_sensor.register_metadata((rs2_frame_metadata_value)RS2_FRAME_METADATA_ACTUAL_FPS, std::make_shared<ds_md_attribute_actual_fps>());
1030 
1031  if (_fw_version >= firmware_version("5.12.7.0"))
1032  {
1034  }
1035 
1036  if (_fw_version >= hdr_firmware_version)
1037  {
1038  // attributes of md_capture_timing
1039  auto md_prop_offset = metadata_raw_mode_offset + offsetof(md_depth_mode, depth_y_mode) + offsetof(md_depth_y_normal_mode, intel_configuration);
1040 
1044  [](const rs2_metadata_type& param) {
1045  // bit mask and offset used to get data from bitfield
1048  }));
1049 
1050  depth_sensor.register_metadata(RS2_FRAME_METADATA_SEQUENCE_ID,
1053  [](const rs2_metadata_type& param) {
1054  // bit mask and offset used to get data from bitfield
1057  }));
1058 
1062  [](const rs2_metadata_type& param) {
1063  // bit mask and offset used to get data from bitfield
1066  }));
1067  }
1068  }
1069 
1071  {
1073 
1074  // frame counter
1076 
1077  // attributes of md_mipi_depth_control structure
1078  auto md_prop_offset = offsetof(metadata_mipi_depth_raw, depth_mode);
1079 
1083  md_prop_offset));
1084 
1088  md_prop_offset));
1089 
1093  md_prop_offset));
1094  depth_sensor.register_metadata(RS2_FRAME_METADATA_EXPOSURE_PRIORITY, // instead of MANUAL_EXPOSURE - not in enum yet
1097  md_prop_offset));
1101  md_prop_offset));
1102  depth_sensor.register_metadata(RS2_FRAME_METADATA_TRIGGER,
1105  md_prop_offset));
1109  md_prop_offset));
1110  depth_sensor.register_metadata(RS2_FRAME_METADATA_PRESET,
1113  md_prop_offset));
1114 
1115  depth_sensor.register_metadata(RS2_FRAME_METADATA_GAIN_LEVEL,
1118  md_prop_offset));
1122  md_prop_offset));
1123  depth_sensor.register_metadata(RS2_FRAME_METADATA_INPUT_WIDTH,
1126  md_prop_offset));
1130  md_prop_offset));
1134  md_prop_offset));
1135  depth_sensor.register_metadata(RS2_FRAME_METADATA_CALIB_INFO,
1138  md_prop_offset));
1139  depth_sensor.register_metadata(RS2_FRAME_METADATA_CRC,
1142  md_prop_offset));
1143 
1144  if (_fw_version >= hdr_firmware_version)
1145  {
1149  [](const rs2_metadata_type& param) {
1150  // bit mask and offset used to get data from bitfield
1153  }));
1154 
1155  depth_sensor.register_metadata(RS2_FRAME_METADATA_SEQUENCE_ID,
1158  [](const rs2_metadata_type& param) {
1159  // bit mask and offset used to get data from bitfield
1162  }));
1163 
1167  [](const rs2_metadata_type& param) {
1168  // bit mask and offset used to get data from bitfield
1171  }));
1172  }
1173  }
1174 
1175  // Check if need change camera name due to number modifications on one device PID.
1177  {
1178  switch (cap)
1179  {
1181  device_name += "F"; // Adding "F" to end of device name if it has IR filter.
1182  break;
1183 
1184  case ds::ds_caps::CAP_IP65:
1185  device_name = std::regex_replace(device_name, std::regex("D455"), "D456"); // Change device name from D455 to D456.
1186  break;
1187 
1188  default:
1189  throw invalid_value_exception("capability '" + ds::ds_capabilities_names.at(cap) + "' is not supported for device name update");
1190  break;
1191  }
1192  }
1193 
1195  {
1197  {
1199  if( it != platform::usb_name_to_spec.end() )
1200  return it->second;
1201  }
1202  return platform::usb_undefined;
1203  }
1204 
1205 
1207  {
1209  //if (dynamic_cast<const platform::playback_backend*>(&(get_context()->get_backend())) != nullptr)
1210  //{
1211  // throw not_implemented_exception("device time not supported for backend.");
1212  //}
1213 
1214  if (!_hw_monitor)
1215  throw wrong_api_call_sequence_exception("_hw_monitor is not initialized yet");
1216 
1218  auto res = _hw_monitor->send(cmd);
1219 
1220  if (res.size() < sizeof(uint32_t))
1221  {
1222  LOG_DEBUG("size(res):" << res.size());
1223  throw std::runtime_error("Not enough bytes returned from the firmware!");
1224  }
1225  uint32_t dt = *(uint32_t*)res.data();
1226  double ts = dt * TIMESTAMP_USEC_TO_MSEC;
1227  return ts;
1228  }
1229 
1231  {
1232  return command{ ds::GLD, 0x1f4 };
1233  }
1234 
1236  {
1237  return command{ ds::FRB, 0x17a000, 0x3f8 };
1238  }
1239 
1240  std::shared_ptr<synthetic_sensor> ds5u_device::create_ds5u_depth_device(std::shared_ptr<context> ctx,
1241  const std::vector<platform::uvc_device_info>& all_device_infos)
1242  {
1243  using namespace ds;
1244 
1245  std::vector<std::shared_ptr<platform::uvc_device>> depth_devices;
1246  for( auto & info : filter_by_mi( all_device_infos, 0 ) ) // Filter just mi=0, DEPTH
1247  depth_devices.push_back( get_backend()->create_uvc_device( info ) );
1248 
1249  std::unique_ptr< frame_timestamp_reader > d400_timestamp_reader_backup( new ds_timestamp_reader() );
1250  std::unique_ptr<frame_timestamp_reader> d400_timestamp_reader_metadata(new ds_timestamp_reader_from_metadata(std::move(d400_timestamp_reader_backup)));
1251 
1252  auto enable_global_time_option = std::shared_ptr<global_time_option>(new global_time_option());
1253  auto raw_depth_ep = std::make_shared<uvc_sensor>(ds::DEPTH_STEREO, std::make_shared<platform::multi_pins_uvc_device>(depth_devices), std::unique_ptr<frame_timestamp_reader>(new global_timestamp_reader(std::move(d400_timestamp_reader_metadata), _tf_keeper, enable_global_time_option)), this);
1254  auto depth_ep = std::make_shared<ds5u_depth_sensor>(this, raw_depth_ep);
1255 
1256  depth_ep->register_option(RS2_OPTION_GLOBAL_TIME_ENABLED, enable_global_time_option);
1257 
1258  raw_depth_ep->register_xu(depth_xu); // make sure the XU is initialized every time we power the camera
1259 
1260  depth_ep->register_processing_block({ {RS2_FORMAT_W10} }, { {RS2_FORMAT_RAW10, RS2_STREAM_INFRARED, 1} }, []() { return std::make_shared<w10_converter>(RS2_FORMAT_RAW10); });
1261  depth_ep->register_processing_block({ {RS2_FORMAT_W10} }, { {RS2_FORMAT_Y10BPACK, RS2_STREAM_INFRARED, 1} }, []() { return std::make_shared<w10_converter>(RS2_FORMAT_Y10BPACK); });
1262 
1263  depth_ep->register_processing_block(processing_block_factory::create_pbf_vector<uyvy_converter>(RS2_FORMAT_UYVY, map_supported_color_formats(RS2_FORMAT_UYVY), RS2_STREAM_INFRARED));
1264 
1265 
1266  return depth_ep;
1267  }
1268 
1269  ds5u_device::ds5u_device( std::shared_ptr< const d400_info > const & dev_info )
1270  : d400_device(dev_info), device(dev_info)
1271  {
1272  using namespace ds;
1273 
1274  // Override the basic d400 sensor with the development version
1275  _depth_device_idx = assign_sensor(create_ds5u_depth_device( dev_info->get_context(), dev_info->get_group().uvc_devices), _depth_device_idx);
1276 
1277  init( dev_info->get_context(), dev_info->get_group() );
1278 
1279  auto& depth_ep = get_depth_sensor();
1280 
1281  // Inhibit specific unresolved options
1282  depth_ep.unregister_option(RS2_OPTION_OUTPUT_TRIGGER_ENABLED);
1283  depth_ep.unregister_option(RS2_OPTION_ERROR_POLLING_ENABLED);
1284  depth_ep.unregister_option(RS2_OPTION_ASIC_TEMPERATURE);
1285  depth_ep.unregister_option(RS2_OPTION_ENABLE_AUTO_WHITE_BALANCE);
1286 
1287  // Enable laser etc.
1288  auto pid = dev_info->get_group().uvc_devices.front().pid;
1289  if (pid != RS_USB2_PID)
1290  {
1291  auto depth_ep = get_raw_depth_sensor();
1292  auto emitter_enabled = std::make_shared<emitter_option>(depth_ep);
1293  depth_ep->register_option(RS2_OPTION_EMITTER_ENABLED, emitter_enabled);
1294 
1295  auto laser_power = std::make_shared<uvc_xu_option<uint16_t>>(depth_ep,
1296  depth_xu,
1298  "Manual laser power in mw. applicable only when laser power mode is set to Manual" );
1299  depth_ep->register_option(RS2_OPTION_LASER_POWER,
1300  std::make_shared< auto_disabling_control >( laser_power,
1301  emitter_enabled,
1302  std::vector< float >{ 0.f, 2.f },
1303  1.f ) );
1304 
1305  depth_ep->register_option(RS2_OPTION_PROJECTOR_TEMPERATURE,
1306  std::make_shared< asic_and_projector_temperature_options >( depth_ep,
1308  }
1309  }
1310 }
librealsense::ds::DEPTH_STEREO
const std::string DEPTH_STEREO
Definition: ds-private.h:256
librealsense::md_mipi_depth_mode::manual_gain
uint8_t manual_gain
Definition: src/metadata.h:309
realdds::topics::control::hwm::key::param3
const std::string param3
librealsense::device::assign_sensor
int assign_sensor(const std::shared_ptr< sensor_interface > &sensor_base, uint8_t idx)
Definition: device.cpp:82
RS2_CAMERA_INFO_PHYSICAL_PORT
@ RS2_CAMERA_INFO_PHYSICAL_PORT
Definition: rs_sensor.h:27
librealsense::synthetic_sensor::close
void close() override
Definition: sensor.cpp:620
librealsense::ds::RECPARAMSGET
@ RECPARAMSGET
Definition: ds-private.h:123
rs2_update_progress_callback_sptr
std::shared_ptr< rs2_update_progress_callback > rs2_update_progress_callback_sptr
Definition: rs_types.hpp:97
remove-ir-pattern-feature.h
librealsense
Definition: algo.h:18
librealsense::ds::d400_calibration_table_id::rgb_calibration_id
@ rgb_calibration_id
d400-private.h
librealsense::md_depth_control_attributes::ae_mode_attribute
@ ae_mode_attribute
librealsense::ds::DS5_LED_PWR
const uint8_t DS5_LED_PWR
Definition: ds-private.h:59
RS2_FRAME_METADATA_FRAME_TIMESTAMP
@ RS2_FRAME_METADATA_FRAME_TIMESTAMP
Definition: rs_frame.h:32
test-fw-update.cmd
list cmd
Definition: test-fw-update.py:141
librealsense::uvc_xu_option< uint8_t >
uint8_t
unsigned char uint8_t
Definition: stdint.h:78
emitter-frequency-feature.h
platform-utils.h
librealsense::d400_device::get_flash_logs_command
command get_flash_logs_command() const
Definition: d400-device.cpp:1235
librealsense::md_configuration::format
uint16_t format
Definition: src/metadata.h:505
librealsense::ds::active_projector
@ active_projector
Definition: ds-private.h:529
RS2_CAMERA_INFO_CAMERA_LOCKED
@ RS2_CAMERA_INFO_CAMERA_LOCKED
Definition: rs_sensor.h:31
rsutils::version
Definition: version.h:20
rmse.x1
int x1
Definition: rmse.py:50
librealsense::d400_device::_depth_stream
std::shared_ptr< stream_interface > _depth_stream
Definition: d400-device.h:99
librealsense::info_container::register_info
void register_info(rs2_camera_info info, const std::string &val)
Definition: sensor.cpp:341
RS2_CAMERA_INFO_RECOMMENDED_FIRMWARE_VERSION
@ RS2_CAMERA_INFO_RECOMMENDED_FIRMWARE_VERSION
Definition: rs_sensor.h:26
RS2_FRAME_METADATA_FRAME_LASER_POWER
@ RS2_FRAME_METADATA_FRAME_LASER_POWER
Definition: rs_frame.h:43
RS2_FRAME_METADATA_SENSOR_TIMESTAMP
@ RS2_FRAME_METADATA_SENSOR_TIMESTAMP
Definition: rs_frame.h:33
librealsense::invalid_value_exception
Definition: librealsense-exception.h:114
librealsense::ds::ir_filter_offset
@ ir_filter_offset
Definition: ds-private.h:527
RS2_FRAME_METADATA_FRAME_LED_POWER
@ RS2_FRAME_METADATA_FRAME_LED_POWER
Definition: rs_frame.h:62
librealsense::ds::DS5_LASER_POWER
const uint8_t DS5_LASER_POWER
Definition: ds-private.h:52
std::to_string
std::string to_string(T value)
Definition: android_helpers.h:16
rs2_extrinsics::translation
float translation[3]
Definition: rs_sensor.h:105
librealsense::ds::DS5_THERMAL_COMPENSATION
const uint8_t DS5_THERMAL_COMPENSATION
Definition: ds-private.h:60
rs-imu-calibration.input
input
Definition: rs-imu-calibration.py:35
librealsense::d400_depth_fourcc_to_rs2_format
std::map< uint32_t, rs2_format > d400_depth_fourcc_to_rs2_format
Definition: d400-device.cpp:55
librealsense::info_container::supports_info
bool supports_info(rs2_camera_info info) const override
Definition: sensor.cpp:335
librealsense::ds::RS457_PID
const uint16_t RS457_PID
Definition: d400-private.h:39
RS2_FORMAT_Y12I
@ RS2_FORMAT_Y12I
Definition: rs_sensor.h:87
librealsense::md_configuration::hw_type
uint8_t hw_type
Definition: src/metadata.h:501
librealsense::md_mipi_depth_control_attributes::exposure_time_attribute
@ exposure_time_attribute
librealsense::md_mipi_depth_mode::calib_info
uint16_t calib_info
Definition: src/metadata.h:298
rs2_extrinsics
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented.
Definition: rs_sensor.h:102
RS2_OPTION_ENABLE_AUTO_EXPOSURE
@ RS2_OPTION_ENABLE_AUTO_EXPOSURE
Definition: rs_option.h:38
librealsense::d400_device::send_receive_raw_data
std::vector< uint8_t > send_receive_raw_data(const std::vector< uint8_t > &input) override
Definition: d400-device.cpp:87
librealsense::sensor_base::assign_stream
void assign_stream(const std::shared_ptr< stream_interface > &stream, std::shared_ptr< stream_profile_interface > target) const
Definition: sensor.cpp:203
librealsense::d400_device::get_new_calibration_table
std::vector< uint8_t > get_new_calibration_table() const
Definition: d400-device.cpp:420
librealsense::md_mipi_depth_mode::exposure_time
uint32_t exposure_time
Definition: src/metadata.h:303
librealsense::param4
Definition: d400-auto-calibration.cpp:163
librealsense::md_mipi_depth_mode::preset
uint8_t preset
Definition: src/metadata.h:308
d400-device.h
librealsense::md_mipi_depth_control_attributes::calibration_info_attribute
@ calibration_info_attribute
RS2_CAMERA_INFO_SERIAL_NUMBER
@ RS2_CAMERA_INFO_SERIAL_NUMBER
Definition: rs_sensor.h:24
librealsense::ds::LASERONCONST
@ LASERONCONST
Definition: ds-private.h:124
librealsense::d400_device::init
void init(std::shared_ptr< context > ctx, const platform::backend_device_group &group)
Definition: d400-device.cpp:522
rsutils::lazy< float >
librealsense::md_mipi_depth_control_attributes::preset_attribute
@ preset_attribute
RS2_FRAME_METADATA_EXPOSURE_PRIORITY
@ RS2_FRAME_METADATA_EXPOSURE_PRIORITY
Definition: rs_frame.h:45
librealsense::ds::imu_acc_chip_id
@ imu_acc_chip_id
Definition: ds-private.h:525
RS2_FORMAT_Y8I
@ RS2_FORMAT_Y8I
Definition: rs_sensor.h:86
librealsense::d400_device::_thermal_monitor
std::shared_ptr< d400_thermal_monitor > _thermal_monitor
Definition: d400-device.h:110
librealsense::d400_device::_new_calib_table_raw
rsutils::lazy< std::vector< uint8_t > > _new_calib_table_raw
Definition: d400-device.h:107
librealsense::synthetic_sensor::get_raw_sensor
const std::shared_ptr< raw_sensor_base > & get_raw_sensor() const
Definition: sensor.h:243
librealsense::d400_device::_depth_device_idx
uint8_t _depth_device_idx
Definition: d400-device.h:104
librealsense::ds::RS415_PID
const uint16_t RS415_PID
Definition: d400-private.h:18
librealsense::md_configuration::SUB_PRESET_BIT_OFFSET_ID
@ SUB_PRESET_BIT_OFFSET_ID
Definition: src/metadata.h:529
RS2_FORMAT_RAW10
@ RS2_FORMAT_RAW10
Definition: rs_sensor.h:74
librealsense::md_depth_control_attributes::emitter_mode_attribute
@ emitter_mode_attribute
test-projection-from-recording.depth_scale
int depth_scale
Definition: test-projection-from-recording.py:48
librealsense::ds::fisheye_sensor_lb
@ fisheye_sensor_lb
Definition: ds-private.h:523
librealsense::d400_depth_sensor::_hdr_cfg
std::shared_ptr< hdr_config > _hdr_cfg
Definition: d400-device.cpp:341
librealsense::md_mipi_depth_control_attributes::input_height_attribute
@ input_height_attribute
librealsense::update_device_name
void update_device_name(std::string &device_name, const ds::ds_caps cap)
Definition: d400-device.cpp:1176
librealsense::md_depth_control_attributes::laser_pwr_attribute
@ laser_pwr_attribute
rs2_intrinsics
Video stream intrinsics.
Definition: rs_types.h:58
data
Definition: parser.hpp:153
librealsense::md_depth_control::exposure_roi_right
uint32_t exposure_roi_right
Definition: src/metadata.h:417
librealsense::group_multiple_fw_calls
auto group_multiple_fw_calls(synthetic_sensor &s, T action) -> decltype(action())
Definition: uvc-sensor.h:101
librealsense::d400_depth_sensor::set_depth_scale
void set_depth_scale(float val)
Definition: d400-device.cpp:304
librealsense::d400_device::get_device_time_ms
virtual double get_device_time_ms() override
Definition: d400-device.cpp:1206
librealsense::metadata_raw_mode_offset
constexpr int metadata_raw_mode_offset
Definition: src/metadata.h:712
librealsense::md_mipi_depth_mode::input_height
uint16_t input_height
Definition: src/metadata.h:312
librealsense::md_mipi_depth_mode::auto_exposure_mode
uint8_t auto_exposure_mode
Definition: src/metadata.h:310
librealsense::md_capture_stats::white_balance
uint32_t white_balance
Definition: src/metadata.h:394
librealsense::md_capture_timing_attributes::sensor_timestamp_attribute
@ sensor_timestamp_attribute
librealsense::d400_depth_sensor::get_recommended_processing_blocks
processing_blocks get_recommended_processing_blocks() const override
Definition: d400-device.cpp:165
realdds::topics::control::hwm::key::param1
const std::string param1
RS2_OPTION_GLOBAL_TIME_ENABLED
@ RS2_OPTION_GLOBAL_TIME_ENABLED
Definition: rs_option.h:81
RS2_OPTION_INTER_CAM_SYNC_MODE
@ RS2_OPTION_INTER_CAM_SYNC_MODE
Definition: rs_option.h:70
string
GLsizei const GLchar *const * string
Definition: glad/glad/glad.h:2861
RS2_CAMERA_INFO_ASIC_SERIAL_NUMBER
@ RS2_CAMERA_INFO_ASIC_SERIAL_NUMBER
Definition: rs_sensor.h:34
librealsense::d400_depth_sensor::_depth_units
std::atomic< float > _depth_units
Definition: d400-device.cpp:339
librealsense::md_depth_control::manual_exposure
uint32_t manual_exposure
Definition: src/metadata.h:412
librealsense::d400_device::get_raw_depth_sensor
std::shared_ptr< uvc_sensor > get_raw_depth_sensor()
Definition: d400-device.h:42
librealsense::d400_device::d400_device
d400_device(std::shared_ptr< const d400_info > const &)
Definition: d400-device.cpp:509
librealsense::ds::DS5_EXT_TRIGGER
const uint8_t DS5_EXT_TRIGGER
Definition: ds-private.h:55
librealsense::platform::usb_spec_names
static const std::map< usb_spec, std::string > usb_spec_names
Definition: usb-types.h:134
realdds::topics::control::hwm::key::param2
const std::string param2
y12i-to-y16y16-mipi.h
librealsense::ds::ds_caps::CAP_IP65
@ CAP_IP65
librealsense::ds::RS455_PID
const uint16_t RS455_PID
Definition: d400-private.h:38
librealsense::uvc_sensor
Definition: uvc-sensor.h:13
librealsense::md_mipi_depth_control_attributes::input_width_attribute
@ input_width_attribute
test-hdr-long.gain_range
gain_range
Definition: test-hdr-long.py:23
LOG_DEBUG
#define LOG_DEBUG(...)
Definition: easyloggingpp.h:70
RS2_FRAME_METADATA_GPIO_INPUT_DATA
@ RS2_FRAME_METADATA_GPIO_INPUT_DATA
Definition: rs_frame.h:64
RS2_CAMERA_INFO_DEBUG_OP_CODE
@ RS2_CAMERA_INFO_DEBUG_OP_CODE
Definition: rs_sensor.h:28
librealsense::md_mipi_depth_control_attributes::manual_gain_attribute
@ manual_gain_attribute
librealsense::RS2_FRAME_METADATA_HEIGHT
@ RS2_FRAME_METADATA_HEIGHT
Definition: frame-additional-data.h:26
RS2_FRAME_METADATA_CRC
@ RS2_FRAME_METADATA_CRC
Definition: rs_frame.h:76
RS2_DEPTH_AUTO_EXPOSURE_ACCELERATED
@ RS2_DEPTH_AUTO_EXPOSURE_ACCELERATED
Definition: rs_option.h:273
run-unit-tests.regex
regex
Definition: run-unit-tests.py:85
librealsense::d400_depth_sensor::get_color_intrinsics
rs2_intrinsics get_color_intrinsics(const stream_profile &profile) const
Definition: d400-device.cpp:220
librealsense::d400_device::_color_stream
std::shared_ptr< stream_interface > _color_stream
Definition: d400-device.h:102
librealsense::ds::is_capability_supports
static bool is_capability_supports(const ds::ds_caps capability, const uint8_t cur_gvd_version)
Definition: d400-private.h:167
librealsense::md_configuration::sku_id
uint8_t sku_id
Definition: src/metadata.h:502
librealsense::device::register_stream_to_extrinsic_group
void register_stream_to_extrinsic_group(const stream_interface &stream, uint32_t groupd_index)
Definition: device.cpp:163
librealsense::processing_block_factory::create_id_pbf
static processing_block_factory create_id_pbf(rs2_format format, rs2_stream stream, int idx=0)
Definition: processing-blocks-factory.cpp:19
librealsense::backend_device::get_pid
uint16_t get_pid() const
Definition: backend-device.h:31
librealsense::d400_device::check_fw_compatibility
bool check_fw_compatibility(const std::vector< uint8_t > &image) const override
Definition: d400-device.cpp:125
librealsense::md_configuration::width
uint16_t width
Definition: src/metadata.h:506
librealsense::d400_depth_sensor::open
void open(const stream_profiles &requests) override
Definition: d400-device.cpp:197
RS2_FRAME_METADATA_SEQUENCE_SIZE
@ RS2_FRAME_METADATA_SEQUENCE_SIZE
Definition: rs_frame.h:67
param
GLenum GLfloat param
Definition: glad/glad/glad.h:1400
librealsense::ds::d400_fw_error_report
const std::map< int, std::string > d400_fw_error_report
Definition: d400-private.h:299
table
GLenum GLenum GLsizei void * table
Definition: glad/glad/glad.h:3584
librealsense::stream_profile
Definition: core/stream-profile.h:15
librealsense::get_ds_depth_recommended_proccesing_blocks
processing_blocks get_ds_depth_recommended_proccesing_blocks()
Definition: ds-device-common.cpp:329
librealsense::platform::usb_spec
usb_spec
Definition: usb-types.h:112
librealsense::d400_depth_sensor::get_depth_scale
float get_depth_scale() const override
Definition: d400-device.cpp:297
librealsense::ds::GVD
@ GVD
Definition: ds-private.h:93
librealsense::wrong_api_call_sequence_exception
Definition: librealsense-exception.h:124
librealsense::ds::RS460_PID
const uint16_t RS460_PID
Definition: d400-private.h:30
librealsense::d400_depth_sensor::get_preset_max_value
float get_preset_max_value() const override
Definition: d400-device.cpp:320
profile::width
int width
Definition: unit-tests-common.h:62
fw-update-unsigned.h
x2
GLdouble GLdouble x2
Definition: glad/glad/glad.h:1781
librealsense::platform::backend_device_group
Definition: backend-device-group.h:50
librealsense::md_mipi_depth_control_attributes::laser_power_attribute
@ laser_power_attribute
depth-formats-converter.h
device.h
RS2_STREAM_COLOR
@ RS2_STREAM_COLOR
Definition: rs_sensor.h:47
librealsense::md_configuration::SUB_PRESET_BIT_MASK_ID
@ SUB_PRESET_BIT_MASK_ID
Definition: src/metadata.h:520
librealsense::d400_device::backup_flash
std::vector< uint8_t > backup_flash(rs2_update_progress_callback_sptr callback) override
Definition: d400-device.cpp:115
librealsense::ds::RS416_RGB_PID
const uint16_t RS416_RGB_PID
Definition: d400-private.h:36
librealsense::d400_device::is_camera_in_advanced_mode
bool is_camera_in_advanced_mode() const
Definition: d400-device.cpp:402
RS2_CAMERA_INFO_PRODUCT_ID
@ RS2_CAMERA_INFO_PRODUCT_ID
Definition: rs_sensor.h:30
librealsense::md_mipi_depth_control_attributes::trigger_attribute
@ trigger_attribute
RS2_FRAME_METADATA_FRAME_COUNTER
@ RS2_FRAME_METADATA_FRAME_COUNTER
Definition: rs_frame.h:31
RS2_RS400_VISUAL_PRESET_REMOVE_IR_PATTERN
@ RS2_RS400_VISUAL_PRESET_REMOVE_IR_PATTERN
Definition: rs_option.h:204
RS2_RS400_VISUAL_PRESET_MEDIUM_DENSITY
@ RS2_RS400_VISUAL_PRESET_MEDIUM_DENSITY
Definition: rs_option.h:203
y8i-to-y8y8.h
librealsense::RS2_FRAME_METADATA_SKU_ID
@ RS2_FRAME_METADATA_SKU_ID
Definition: frame-additional-data.h:23
librealsense::environment::get_instance
static environment & get_instance()
Definition: environment.cpp:247
librealsense::rs_fourcc
uint32_t rs_fourcc(const T a, const T b, const T c, const T d)
Definition: fourcc.h:13
dt
double dt
Definition: boing.c:106
librealsense::roi_sensor_base
Definition: roi.h:38
RS2_CAMERA_INFO_NAME
@ RS2_CAMERA_INFO_NAME
Definition: rs_sensor.h:23
librealsense::md_mipi_depth_mode::laser_power
uint16_t laser_power
Definition: src/metadata.h:305
librealsense::ds5u_device::create_ds5u_depth_device
std::shared_ptr< synthetic_sensor > create_ds5u_depth_device(std::shared_ptr< context > ctx, const std::vector< platform::uvc_device_info > &all_device_infos)
Definition: d400-device.cpp:1240
librealsense::d400_device::register_features
void register_features()
Definition: d400-device.cpp:956
LOG_WARNING
#define LOG_WARNING(...)
Definition: easyloggingpp.h:72
librealsense::d400_depth_sensor::init_stream_profiles
stream_profiles init_stream_profiles() override
Definition: d400-device.cpp:235
librealsense::d400_device::_hw_monitor
std::shared_ptr< hw_monitor > _hw_monitor
Definition: d400-device.h:94
RS2_FRAME_METADATA_EXPOSURE_ROI_LEFT
@ RS2_FRAME_METADATA_EXPOSURE_ROI_LEFT
Definition: rs_frame.h:46
librealsense::d400_device::get_depth_sensor
synthetic_sensor & get_depth_sensor()
Definition: d400-device.h:37
firmware-version.h
RS2_FORMAT_Z16
@ RS2_FORMAT_Z16
Definition: rs_sensor.h:64
RS2_FRAME_METADATA_EXPOSURE_ROI_RIGHT
@ RS2_FRAME_METADATA_EXPOSURE_ROI_RIGHT
Definition: rs_frame.h:47
RS2_FORMAT_W10
@ RS2_FORMAT_W10
Definition: rs_sensor.h:90
RS2_FRAME_METADATA_PRESET
@ RS2_FRAME_METADATA_PRESET
Definition: rs_frame.h:71
librealsense::make_attribute_parser
std::shared_ptr< md_attribute_parser_base > make_attribute_parser(Attribute S::*attribute, Flag flag, unsigned long long offset, attrib_modifyer mod=nullptr)
A helper function to create a specialized attribute parser. Return it as a pointer to a base-class.
Definition: metadata-parser.h:181
librealsense::platform::filter_by_mi
std::vector< uvc_device_info > filter_by_mi(const std::vector< uvc_device_info > &devices, uint32_t mi)
Definition: platform-utils.cpp:134
librealsense::md_mipi_depth_control_attributes::projector_mode_attribute
@ projector_mode_attribute
y12i-to-y16y16.h
test-d405-calibration-stream.pid
pid
Definition: test-d405-calibration-stream.py:12
librealsense::ds::ds_caps::CAP_IR_FILTER
@ CAP_IR_FILTER
librealsense::platform::backend_device_group::usb_devices
std::vector< usb_device_info > usb_devices
Definition: backend-device-group.h:76
librealsense::md_mipi_depth_control_attributes::hw_timestamp_attribute
@ hw_timestamp_attribute
profile::height
int height
Definition: unit-tests-common.h:63
librealsense::option_range
Definition: option-interface.h:14
val
GLuint GLfloat * val
Definition: glad/glad/glad.h:3411
mask
GLint GLuint mask
Definition: glad/glad/glad.h:1460
librealsense::md_mipi_depth_mode::crc
uint32_t crc
Definition: src/metadata.h:314
librealsense::ds::FRB
@ FRB
Definition: ds-private.h:86
librealsense::ds::RS416_PID
const uint16_t RS416_PID
Definition: d400-private.h:34
librealsense::md_configuration_attributes::gpio_input_data_attribute
@ gpio_input_data_attribute
RS2_OPTION_GAIN
@ RS2_OPTION_GAIN
Definition: rs_option.h:32
librealsense::d400_device::_polling_error_handler
std::shared_ptr< polling_error_handler > _polling_error_handler
Definition: d400-device.h:109
RS2_FORMAT_YUYV
@ RS2_FORMAT_YUYV
Definition: rs_sensor.h:67
librealsense::ds::DS5_HWMONITOR
const uint8_t DS5_HWMONITOR
Definition: ds-private.h:49
librealsense::depth_sensor
Definition: depth-sensor.h:9
librealsense::d400_device::_is_locked
bool _is_locked
Definition: d400-device.h:114
librealsense::md_mipi_depth_control_attributes::sub_preset_info_attribute
@ sub_preset_info_attribute
RS2_RS400_VISUAL_PRESET_COUNT
@ RS2_RS400_VISUAL_PRESET_COUNT
Definition: rs_option.h:205
RS2_OPTION_THERMAL_COMPENSATION
@ RS2_OPTION_THERMAL_COMPENSATION
Definition: rs_option.h:101
librealsense::device::add_sensor
int add_sensor(const std::shared_ptr< sensor_interface > &sensor_base)
Definition: device.cpp:76
librealsense::md_mipi_depth_mode::manual_exposure
uint32_t manual_exposure
Definition: src/metadata.h:304
uint32_t
unsigned int uint32_t
Definition: stdint.h:80
librealsense::val_in_range
bool val_in_range(const T &val, const std::initializer_list< T > &list)
Definition: src/types.h:66
librealsense::d400_depth_sensor::d400_depth_sensor
d400_depth_sensor(d400_device *owner, std::shared_ptr< uvc_sensor > uvc_sensor)
Definition: d400-device.cpp:156
librealsense::ds::DS5_HARDWARE_PRESET
const uint8_t DS5_HARDWARE_PRESET
Definition: ds-private.h:53
RS2_CAMERA_INFO_FIRMWARE_VERSION
@ RS2_CAMERA_INFO_FIRMWARE_VERSION
Definition: rs_sensor.h:25
librealsense::md_configuration::SUB_PRESET_BIT_OFFSET_SEQUENCE_ID
@ SUB_PRESET_BIT_OFFSET_SEQUENCE_ID
Definition: src/metadata.h:531
librealsense::d400_device::_color_calib_table_raw
rsutils::lazy< std::vector< uint8_t > > _color_calib_table_raw
Definition: d400-device.h:112
librealsense::ds::d400_calibration_table_id::coefficients_table_id
@ coefficients_table_id
RS2_OPTION_LED_POWER
@ RS2_OPTION_LED_POWER
Definition: rs_option.h:88
RS2_OPTION_HARDWARE_PRESET
@ RS2_OPTION_HARDWARE_PRESET
Definition: rs_option.h:80
depth-sensor.h
librealsense::d400_device::_fw_version
firmware_version _fw_version
Definition: d400-device.h:95
librealsense::ds::d400_hid_bmi_085_pid
static const std::set< std::uint16_t > d400_hid_bmi_085_pid
Definition: d400-private.h:92
RS2_DEPTH_AUTO_EXPOSURE_REGULAR
@ RS2_DEPTH_AUTO_EXPOSURE_REGULAR
Definition: rs_option.h:272
librealsense::ds::RS410_PID
const uint16_t RS410_PID
Definition: d400-private.h:17
librealsense::md_depth_mode
Definition: src/metadata.h:677
librealsense::ds::depth_sensor_type
@ depth_sensor_type
Definition: ds-private.h:528
librealsense::ds::REGISTER_CLOCK_0
const uint32_t REGISTER_CLOCK_0
Definition: ds-private.h:73
RS2_OPTION_OUTPUT_TRIGGER_ENABLED
@ RS2_OPTION_OUTPUT_TRIGGER_ENABLED
Definition: rs_option.h:54
librealsense::platform::uvc_header::timestamp
uint32_t timestamp
Definition: platform/uvc-device.h:66
librealsense::d400_device::_device_capabilities
ds::ds_caps _device_capabilities
Definition: d400-device.h:97
librealsense::ds::ip65_sealed_offset
@ ip65_sealed_offset
Definition: ds-private.h:526
librealsense::md_capture_stat_attributes::white_balance_attribute
@ white_balance_attribute
RS2_OPTION_STEREO_BASELINE
@ RS2_OPTION_STEREO_BASELINE
Definition: rs_option.h:68
librealsense::d400_device::get_d400_raw_calibration_table
std::vector< uint8_t > get_d400_raw_calibration_table(ds::d400_calibration_table_id table_id) const
Definition: d400-device.cpp:414
librealsense::md_configuration::SUB_PRESET_BIT_MASK_SEQUENCE_ID
@ SUB_PRESET_BIT_MASK_SEQUENCE_ID
Definition: src/metadata.h:522
librealsense::HW_MONITOR_BUFFER_SIZE
const uint16_t HW_MONITOR_BUFFER_SIZE
Definition: hw-monitor.h:45
librealsense::md_configuration::SUB_PRESET_BIT_MASK_SEQUENCE_SIZE
@ SUB_PRESET_BIT_MASK_SEQUENCE_SIZE
Definition: src/metadata.h:521
RS2_FORMAT_Y10BPACK
@ RS2_FORMAT_Y10BPACK
Definition: rs_sensor.h:83
d400-options.h
librealsense::platform::usb_name_to_spec
static const std::map< std::string, usb_spec > usb_name_to_spec
Definition: usb-types.h:124
d400-color.h
librealsense::make_rs400_sensor_ts_parser
std::shared_ptr< md_attribute_parser_base > make_rs400_sensor_ts_parser(std::shared_ptr< md_attribute_parser_base > frame_ts_parser, std::shared_ptr< md_attribute_parser_base > sensor_ts_parser)
A helper function to create a specialized parser for RS4xx sensor timestamp.
Definition: metadata-parser.h:393
RS2_FRAME_METADATA_FRAME_EMITTER_MODE
@ RS2_FRAME_METADATA_FRAME_EMITTER_MODE
Definition: rs_frame.h:61
librealsense::ds::DS5_ENABLE_AUTO_EXPOSURE
const uint8_t DS5_ENABLE_AUTO_EXPOSURE
Definition: ds-private.h:58
librealsense::ds::MRD
@ MRD
Definition: ds-private.h:85
librealsense::md_mipi_depth_mode::hw_timestamp
uint32_t hw_timestamp
Definition: src/metadata.h:301
librealsense::TIMESTAMP_USEC_TO_MSEC
static const double TIMESTAMP_USEC_TO_MSEC
Definition: src/types.h:56
librealsense::ds_timestamp_reader_from_metadata
Definition: ds-timestamp.h:13
librealsense::ds::rs400_sku_names
static const std::map< std::uint16_t, std::string > rs400_sku_names
Definition: d400-private.h:102
librealsense::ds::rgb_sensor
@ rgb_sensor
Definition: ds-private.h:530
librealsense::d400_depth_sensor::get_intrinsics
rs2_intrinsics get_intrinsics(const stream_profile &profile) const override
Definition: d400-device.cpp:170
librealsense::ds::fisheye_sensor_hb
@ fisheye_sensor_hb
Definition: ds-private.h:524
librealsense::ds::RS435_RGB_PID
const uint16_t RS435_RGB_PID
Definition: d400-private.h:31
librealsense::ds::gvd_version_offset
@ gvd_version_offset
Definition: ds-private.h:518
librealsense::d400_device::enter_update_state
void enter_update_state() const override
Definition: d400-device.cpp:110
librealsense::global_time_interface::_tf_keeper
std::shared_ptr< time_diff_keeper > _tf_keeper
Definition: global_timestamp_reader.h:114
librealsense::RS2_FRAME_METADATA_FORMAT
@ RS2_FRAME_METADATA_FORMAT
Definition: frame-additional-data.h:24
librealsense::ds::RS_USB2_PID
const uint16_t RS_USB2_PID
Definition: d400-private.h:21
RS2_FORMAT_RAW16
@ RS2_FORMAT_RAW16
Definition: rs_sensor.h:75
librealsense::md_configuration::height
uint16_t height
Definition: src/metadata.h:507
librealsense::d400_device::hardware_reset
void hardware_reset() override
Definition: d400-device.cpp:103
RS2_OPTION_DEPTH_UNITS
@ RS2_OPTION_DEPTH_UNITS
Definition: rs_option.h:56
librealsense::md_depth_control::ledPower
uint16_t ledPower
Definition: src/metadata.h:423
RS2_OPTION_ASIC_TEMPERATURE
@ RS2_OPTION_ASIC_TEMPERATURE
Definition: rs_option.h:51
librealsense::ds::ds_caps::CAP_UNDEFINED
@ CAP_UNDEFINED
rs2_metadata_type
long long rs2_metadata_type
Definition: rs_types.h:272
librealsense::ds5u_device
Definition: d400-device.h:120
librealsense::md_depth_control_attributes::roi_attribute
@ roi_attribute
D4XX_RECOMMENDED_FIRMWARE_VERSION
#define D4XX_RECOMMENDED_FIRMWARE_VERSION
Definition: common/fw/firmware-version.h:6
librealsense::md_configuration_attributes::sub_preset_info_attribute
@ sub_preset_info_attribute
librealsense::md_mipi_depth_control_attributes::optical_timestamp_attribute
@ optical_timestamp_attribute
librealsense::d400_device::register_metadata_mipi
void register_metadata_mipi(const synthetic_sensor &depth_sensor, const firmware_version &hdr_firmware_version) const
Definition: d400-device.cpp:1070
librealsense::features_container::register_feature
void register_feature(std::shared_ptr< feature_interface > feature)
Definition: features-container.h:38
librealsense::ds_timestamp_reader_from_metadata_mipi
Definition: ds-timestamp.h:36
librealsense::d400_depth_sensor
Definition: d400-device.cpp:149
librealsense::global_time_interface
Definition: global_timestamp_reader.h:111
librealsense::ds::try_get_d400_intrinsic_by_resolution_new
bool try_get_d400_intrinsic_by_resolution_new(const vector< uint8_t > &raw_data, uint32_t width, uint32_t height, rs2_intrinsics *result)
Definition: d400-private.cpp:294
librealsense::md_depth_control::exposure_roi_top
uint32_t exposure_roi_top
Definition: src/metadata.h:418
RS2_FORMAT_MJPEG
@ RS2_FORMAT_MJPEG
Definition: rs_sensor.h:85
librealsense::md_depth_control_attributes::exposure_attribute
@ exposure_attribute
librealsense::ds::get_d400_intrinsic_by_resolution
rs2_intrinsics get_d400_intrinsic_by_resolution(const vector< uint8_t > &raw_data, d400_calibration_table_id table_id, uint32_t width, uint32_t height)
Definition: d400-private.cpp:105
librealsense::md_depth_control::exposure_roi_bottom
uint32_t exposure_roi_bottom
Definition: src/metadata.h:419
RS2_STREAM_DEPTH
@ RS2_STREAM_DEPTH
Definition: rs_sensor.h:46
librealsense::ds5u_depth_sensor::ds5u_depth_sensor
ds5u_depth_sensor(ds5u_device *owner, std::shared_ptr< uvc_sensor > uvc_sensor)
Definition: d400-device.cpp:347
d400-info.h
librealsense::firmware_version
rsutils::version firmware_version
Definition: src/firmware-version.h:11
librealsense::md_mipi_depth_mode::optical_timestamp
uint32_t optical_timestamp
Definition: src/metadata.h:302
librealsense::ds::RS435I_PID
const uint16_t RS435I_PID
Definition: d400-private.h:33
librealsense::environment::get_extrinsics_graph
extrinsics_graph & get_extrinsics_graph()
Definition: environment.cpp:253
d400-thermal-monitor.h
librealsense::md_depth_control::exposure_priority
uint32_t exposure_priority
Definition: src/metadata.h:415
image.h
backend.h
librealsense::md_mipi_depth_mode::sub_preset_info
uint32_t sub_preset_info
Definition: src/metadata.h:313
librealsense::ds::ds_caps
ds_caps
Definition: ds-private.h:191
librealsense::md_configuration::SUB_PRESET_BIT_OFFSET_SEQUENCE_SIZE
@ SUB_PRESET_BIT_OFFSET_SEQUENCE_SIZE
Definition: src/metadata.h:530
librealsense::d400_device::register_metadata
void register_metadata(const synthetic_sensor &depth_sensor, const firmware_version &hdr_firmware_version) const
Definition: d400-device.cpp:980
librealsense::options_container::get_option
option & get_option(rs2_option id) override
Definition: options-container.h:32
librealsense::options_container::supports_option
bool supports_option(rs2_option id) const override
Definition: options-container.h:25
librealsense::to_profile
stream_profile to_profile(const stream_profile_interface *sp)
Definition: src/stream.h:222
RS2_CAMERA_INFO_DFU_DEVICE_PATH
@ RS2_CAMERA_INFO_DFU_DEVICE_PATH
Definition: rs_sensor.h:37
rsutils::string::hexdump
Definition: hexdump.h:24
RS2_FRAME_METADATA_SEQUENCE_NAME
@ RS2_FRAME_METADATA_SEQUENCE_NAME
Definition: rs_frame.h:65
librealsense::md_depth_control::auto_exposure_mode
uint32_t auto_exposure_mode
Definition: src/metadata.h:414
librealsense::metadata_mipi_depth_raw
metadata_mipi_raw - metadata structure layout as transmitted and received by backend
Definition: src/metadata.h:716
RS2_OPTION_EXPOSURE
@ RS2_OPTION_EXPOSURE
Definition: rs_option.h:31
librealsense::ds::DS5_EXPOSURE
const uint8_t DS5_EXPOSURE
Definition: ds-private.h:51
color-formats-converter.h
librealsense::md_configuration_attributes::hw_type_attribute
@ hw_type_attribute
RS2_FRAME_METADATA_SEQUENCE_ID
@ RS2_FRAME_METADATA_SEQUENCE_ID
Definition: rs_frame.h:66
librealsense::synthetic_sensor
Definition: sensor.h:208
librealsense::md_depth_y_normal_mode
Definition: src/metadata.h:630
librealsense::d400_device::get_firmware_logs_command
command get_firmware_logs_command() const
Definition: d400-device.cpp:1230
librealsense::ds::RS400_IMU_PID
const uint16_t RS400_IMU_PID
Definition: d400-private.h:24
RS2_FRAME_METADATA_AUTO_EXPOSURE
@ RS2_FRAME_METADATA_AUTO_EXPOSURE
Definition: rs_frame.h:37
librealsense::stream
Definition: src/stream.h:30
librealsense::synthetic_sensor::open
void open(const stream_profiles &requests) override
Definition: sensor.cpp:585
librealsense::ds::I2C_IMU_BMI055_ID_ACC
const uint8_t I2C_IMU_BMI055_ID_ACC
Definition: ds-private.h:535
RS2_CAMERA_INFO_USB_TYPE_DESCRIPTOR
@ RS2_CAMERA_INFO_USB_TYPE_DESCRIPTOR
Definition: rs_sensor.h:32
fps.info
info
Definition: fps.py:50
RS2_FRAME_METADATA_CALIB_INFO
@ RS2_FRAME_METADATA_CALIB_INFO
Definition: rs_frame.h:75
hexdump.h
librealsense::platform::backend_device_group::uvc_devices
std::vector< uvc_device_info > uvc_devices
Definition: backend-device-group.h:75
librealsense::d400_depth_sensor::_stereo_baseline_mm
float _stereo_baseline_mm
Definition: d400-device.cpp:340
librealsense::on_frame_md
std::function< void(frame_additional_data &data)> on_frame_md
Definition: sensor.h:37
librealsense::extrinsics_graph::register_same_extrinsics
void register_same_extrinsics(const stream_interface &from, const stream_interface &to)
Definition: environment.cpp:27
d400-nonmonochrome.h
librealsense::d400_device::build_command
std::vector< uint8_t > build_command(uint32_t opcode, uint32_t param1=0, uint32_t param2=0, uint32_t param3=0, uint32_t param4=0, uint8_t const *data=nullptr, size_t dataLength=0) const override
Definition: d400-device.cpp:92
hdr-config.h
librealsense::sensor_interface::stream_profiles
std::vector< std::shared_ptr< stream_profile_interface > > stream_profiles
Definition: sensor-interface.h:38
librealsense::frame_additional_data
Definition: frame-additional-data.h:53
librealsense::auto_calibrated::set_hw_monitor_for_auto_calib
void set_hw_monitor_for_auto_calib(std::shared_ptr< hw_monitor > hwm)
Definition: d400-auto-calibration.cpp:2570
amplitude-factor-feature.h
RS2_OPTION_LASER_POWER
@ RS2_OPTION_LASER_POWER
Definition: rs_option.h:41
RS2_OPTION_EMITTER_ALWAYS_ON
@ RS2_OPTION_EMITTER_ALWAYS_ON
Definition: rs_option.h:100
librealsense::video_sensor_interface
Definition: video.h:11
RS2_FRAME_METADATA_WHITE_BALANCE
@ RS2_FRAME_METADATA_WHITE_BALANCE
Definition: rs_frame.h:38
librealsense::md_mipi_depth_control_attributes::auto_exposure_mode_attribute
@ auto_exposure_mode_attribute
librealsense::video_stream_profile_interface
Definition: video.h:17
librealsense::d400_device::update_flash
void update_flash(const std::vector< uint8_t > &image, rs2_update_progress_callback_sptr callback, int update_mode) override
Definition: d400-device.cpp:120
librealsense::d400_device::parse_device_capabilities
ds::ds_caps parse_device_capabilities(const std::vector< uint8_t > &gvd_buf) const
Definition: d400-device.cpp:430
librealsense::md_capture_timing::frame_counter
uint32_t frame_counter
Definition: src/metadata.h:356
hw_mon_over_xu
constexpr bool hw_mon_over_xu
Definition: d400-device.cpp:50
librealsense::platform::usb_undefined
@ usb_undefined
Definition: usb-types.h:113
RS2_OPTION_ERROR_POLLING_ENABLED
@ RS2_OPTION_ERROR_POLLING_ENABLED
Definition: rs_option.h:52
librealsense::ds::DS5_DEPTH_AUTO_EXPOSURE_MODE
const uint8_t DS5_DEPTH_AUTO_EXPOSURE_MODE
Definition: ds-private.h:62
assert
#define assert(condition)
Definition: lz4.c:245
RS2_CAMERA_INFO_FIRMWARE_UPDATE_ID
@ RS2_CAMERA_INFO_FIRMWARE_UPDATE_ID
Definition: rs_sensor.h:35
librealsense::ds::RS405_PID
const uint16_t RS405_PID
Definition: d400-private.h:37
librealsense::backend_device::_pid
uint16_t _pid
Definition: backend-device.h:37
librealsense::ds::GLD
@ GLD
Definition: ds-private.h:92
librealsense::d400_device::_recommended_fw_version
firmware_version _recommended_fw_version
Definition: d400-device.h:96
librealsense::depth_stereo_sensor
Definition: depth-sensor.h:18
librealsense::d400_depth_sensor::set_frame_metadata_modifier
void set_frame_metadata_modifier(on_frame_md callback) override
Definition: d400-device.cpp:188
rsutils::string::from
Definition: from.h:19
librealsense::RS2_FRAME_METADATA_WIDTH
@ RS2_FRAME_METADATA_WIDTH
Definition: frame-additional-data.h:25
librealsense::d400_device::create_depth_device
std::shared_ptr< synthetic_sensor > create_depth_device(std::shared_ptr< context > ctx, const std::vector< platform::uvc_device_info > &all_device_infos)
Definition: d400-device.cpp:470
auto-exposure-limit-feature.h
RS2_FRAME_METADATA_TRIGGER
@ RS2_FRAME_METADATA_TRIGGER
Definition: rs_frame.h:70
librealsense::md_configuration_attributes::width_attribute
@ width_attribute
librealsense::md_depth_control::manual_gain
uint32_t manual_gain
Definition: src/metadata.h:411
signed_fw_size
const unsigned int signed_fw_size
Definition: rs_internal.h:25
gain-limit-feature.h
librealsense::platform::usb3_type
@ usb3_type
Definition: usb-types.h:119
RS2_FRAME_METADATA_GAIN_LEVEL
@ RS2_FRAME_METADATA_GAIN_LEVEL
Definition: rs_frame.h:35
RS2_FORMAT_UYVY
@ RS2_FORMAT_UYVY
Definition: rs_sensor.h:77
p
double p[GRIDW][GRIDH]
Definition: wave.c:109
processing_blocks
Definition: rs-benchmark.cpp:165
librealsense::make_uvc_header_parser
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.
Definition: metadata-parser.h:222
librealsense::md_mipi_depth_mode::input_width
uint16_t input_width
Definition: src/metadata.h:311
test-fps.ds
ds
Definition: test-fps.py:77
librealsense::ds::HWRST
@ HWRST
Definition: ds-private.h:98
RS2_FORMAT_Y16
@ RS2_FORMAT_Y16
Definition: rs_sensor.h:73
RS2_OPTION_EMITTER_ENABLED
@ RS2_OPTION_EMITTER_ENABLED
Definition: rs_option.h:46
librealsense::md_depth_control_attributes::led_power_attribute
@ led_power_attribute
librealsense::sensor_base::_metadata_modifier
on_frame_md _metadata_modifier
Definition: sensor.h:141
librealsense::ds::d400_hid_bmi_055_pid
static const std::set< std::uint16_t > d400_hid_bmi_055_pid
Definition: d400-private.h:86
librealsense::d400_device::get_stereo_baseline_mm
float get_stereo_baseline_mm() const
Definition: d400-device.cpp:407
librealsense::md_configuration::sub_preset_info
uint32_t sub_preset_info
Definition: src/metadata.h:515
RS2_FRAME_METADATA_FRAME_LASER_POWER_MODE
@ RS2_FRAME_METADATA_FRAME_LASER_POWER_MODE
Definition: rs_frame.h:44
librealsense::ds_timestamp_reader
Definition: ds-timestamp.h:68
RS2_CAMERA_INFO_ADVANCED_MODE
@ RS2_CAMERA_INFO_ADVANCED_MODE
Definition: rs_sensor.h:29
librealsense::frame_timestamp_reader
Definition: sensor.h:39
librealsense::md_depth_control::exposure_roi_left
uint32_t exposure_roi_left
Definition: src/metadata.h:416
librealsense::ds::depth_xu
const platform::extension_unit depth_xu
Definition: ds-private.h:67
RS2_FRAME_METADATA_ACTUAL_EXPOSURE
@ RS2_FRAME_METADATA_ACTUAL_EXPOSURE
Definition: rs_frame.h:34
librealsense::extrinsics_graph::register_extrinsics
void register_extrinsics(const stream_interface &from, const stream_interface &to, std::weak_ptr< rsutils::lazy< rs2_extrinsics > > extr)
Definition: environment.cpp:50
librealsense::backend_device::get_backend
std::shared_ptr< platform::backend > get_backend()
Definition: backend-device-factory.cpp:118
RS2_FRAME_METADATA_EXPOSURE_ROI_BOTTOM
@ RS2_FRAME_METADATA_EXPOSURE_ROI_BOTTOM
Definition: rs_frame.h:49
environment.h
RS2_FORMAT_Y8
@ RS2_FORMAT_Y8
Definition: rs_sensor.h:72
librealsense::synthetic_sensor::init_stream_profiles
virtual stream_profiles init_stream_profiles() override
Definition: sensor.cpp:560
librealsense::md_configuration_attributes::sku_id_attribute
@ sku_id_attribute
librealsense::ds::extract_firmware_version_string
std::string extract_firmware_version_string(const std::vector< uint8_t > &fw_image)
Definition: d400-private.cpp:88
image
GLenum GLenum GLsizei void * image
Definition: glad/glad/glad.h:3587
librealsense::md_configuration_attributes::height_attribute
@ height_attribute
RS2_OPTION_SEQUENCE_NAME
@ RS2_OPTION_SEQUENCE_NAME
Definition: rs_option.h:106
librealsense::md_depth_control::laser_power
uint32_t laser_power
Definition: src/metadata.h:413
librealsense::ds::imu_sensor
@ imu_sensor
Definition: ds-private.h:531
RS2_FRAME_METADATA_SUB_PRESET_INFO
@ RS2_FRAME_METADATA_SUB_PRESET_INFO
Definition: rs_frame.h:74
librealsense::ds::is_camera_locked_offset
@ is_camera_locked_offset
Definition: ds-private.h:520
test-depth_ae_mode.fw_version
fw_version
Definition: test-depth_ae_mode.py:14
librealsense::backend_device
Definition: backend-device.h:20
test-projection-from-recording.ctx
ctx
Definition: test-projection-from-recording.py:16
librealsense::md_mipi_depth_mode::projector_mode
uint8_t projector_mode
Definition: src/metadata.h:307
RS2_STREAM_INFRARED
@ RS2_STREAM_INFRARED
Definition: rs_sensor.h:48
librealsense::md_capture_timing::sensor_timestamp
uint32_t sensor_timestamp
Definition: src/metadata.h:357
librealsense::d400_depth_fourcc_to_rs2_stream
std::map< uint32_t, rs2_stream > d400_depth_fourcc_to_rs2_stream
Definition: d400-device.cpp:71
librealsense::ds5u_depth_sensor::_owner
const ds5u_device * _owner
Definition: d400-device.cpp:399
librealsense::global_time_option
Definition: global_timestamp_reader.h:13
librealsense::md_configuration::gpioInputData
uint8_t gpioInputData
Definition: src/metadata.h:514
RS2_OPTION_DEPTH_AUTO_EXPOSURE_MODE
@ RS2_OPTION_DEPTH_AUTO_EXPOSURE_MODE
Definition: rs_option.h:123
RS2_FORMAT_Z16H
@ RS2_FORMAT_Z16H
Definition: rs_sensor.h:91
rs2::textual_icons::lock
static const textual_icon lock
Definition: device-model.h:186
metadata.h
librealsense::d400_device::_coefficients_table_raw
rsutils::lazy< std::vector< uint8_t > > _coefficients_table_raw
Definition: d400-device.h:106
auto-exposure-roi-feature.h
RS2_OPTION_EMITTER_ON_OFF
@ RS2_OPTION_EMITTER_ON_OFF
Definition: rs_option.h:74
stream.h
librealsense::identity_matrix
rs2_extrinsics identity_matrix()
Definition: src/pose.h:60
librealsense::md_mipi_depth_control_attributes::crc_attribute
@ crc_attribute
librealsense::ds::GETINTCAL
@ GETINTCAL
Definition: ds-private.h:94
librealsense::ds5u_device::ds5u_device
ds5u_device(std::shared_ptr< const d400_info > const &)
Definition: d400-device.cpp:1269
librealsense::global_timestamp_reader
Definition: global_timestamp_reader.h:91
librealsense::md_capture_timing_attributes::frame_counter_attribute
@ frame_counter_attribute
librealsense::md_mipi_depth_control_attributes::manual_exposure_attribute
@ manual_exposure_attribute
librealsense::ds::ds_capabilities_names
static const std::map< ds_caps, std::string > ds_capabilities_names
Definition: ds-private.h:208
librealsense::auto_calibrated
Definition: d400-auto-calibration.h:29
librealsense::ds::d400_calibration_table_id
d400_calibration_table_id
Definition: d400-private.h:181
librealsense::d400_device::_left_ir_stream
std::shared_ptr< stream_interface > _left_ir_stream
Definition: d400-device.h:100
test-emitter-frequency.device_name
device_name
Definition: test-emitter-frequency.py:26
RS2_OPTION_SEQUENCE_ID
@ RS2_OPTION_SEQUENCE_ID
Definition: rs_option.h:108
librealsense::d400_device::_left_right_extrinsics
std::shared_ptr< rsutils::lazy< rs2_extrinsics > > _left_right_extrinsics
Definition: d400-device.h:111
RS2_FRAME_METADATA_EXPOSURE_ROI_TOP
@ RS2_FRAME_METADATA_EXPOSURE_ROI_TOP
Definition: rs_frame.h:48
end
GLuint GLuint end
Definition: glad/glad/glad.h:2395
librealsense::d400_device::_ds_device_common
std::shared_ptr< ds_device_common > _ds_device_common
Definition: d400-device.h:71
librealsense::d400_depth_sensor::get_stereo_baseline_mm
float get_stereo_baseline_mm() const override
Definition: d400-device.cpp:318
RS2_FRAME_METADATA_ACTUAL_FPS
@ RS2_FRAME_METADATA_ACTUAL_FPS
Definition: rs_frame.h:42
librealsense::option::query
virtual float query() const =0
librealsense::d400_device::_right_ir_stream
std::shared_ptr< stream_interface > _right_ir_stream
Definition: d400-device.h:101
RS2_OPTION_PROJECTOR_TEMPERATURE
@ RS2_OPTION_PROJECTOR_TEMPERATURE
Definition: rs_option.h:53
librealsense::md_mipi_depth_mode::trigger
uint16_t trigger
Definition: src/metadata.h:306
rs2_frame_metadata_value
rs2_frame_metadata_value
Per-Frame-Metadata is the set of read-only properties that might be exposed for each individual frame...
Definition: rs_frame.h:29
it
static auto it
Definition: openvino-face-detection.cpp:375
librealsense::md_depth_control_attributes::exposure_priority_attribute
@ exposure_priority_attribute
librealsense::d400_depth_sensor::get_hdr_config
std::shared_ptr< hdr_config > get_hdr_config()
Definition: d400-device.cpp:316
librealsense::d400_depth_sensor::_owner
const d400_device * _owner
Definition: d400-device.cpp:338
test-depth.result
result
Definition: test-depth.py:183
librealsense::md_configuration_attributes::format_attribute
@ format_attribute
librealsense::ds::RS400_PID
const uint16_t RS400_PID
Definition: d400-private.h:16
librealsense::ds5u_depth_sensor
Definition: d400-device.cpp:344
s
GLdouble s
Definition: glad/glad/glad.h:2441
librealsense::device
Definition: device.h:35
ds-timestamp.h
librealsense::d400_device::get_usb_spec
platform::usb_spec get_usb_spec() const
Definition: d400-device.cpp:1194
librealsense::info_container::get_info
const std::string & get_info(rs2_camera_info info) const override
Definition: sensor.cpp:360
RS2_CAMERA_INFO_PRODUCT_LINE
@ RS2_CAMERA_INFO_PRODUCT_LINE
Definition: rs_sensor.h:33
librealsense::d400_depth_sensor::init_hdr_config
void init_hdr_config(const option_range &exposure_range, const option_range &gain_range)
Definition: d400-device.cpp:310
librealsense::ds5u_depth_sensor::init_stream_profiles
stream_profiles init_stream_profiles() override
Definition: d400-device.cpp:352
RS2_FRAME_METADATA_INPUT_WIDTH
@ RS2_FRAME_METADATA_INPUT_WIDTH
Definition: rs_frame.h:72
librealsense::ds::d400_device_to_fw_min_version
static std::map< uint16_t, std::string > d400_device_to_fw_min_version
Definition: d400-private.h:129
metadata-parser.h
librealsense::md_depth_control_attributes::gain_attribute
@ gain_attribute
librealsense::md_depth_control::emitterMode
uint8_t emitterMode
Definition: src/metadata.h:421
librealsense::command
Definition: hw-monitor.h:247
RS2_FORMAT_BGR8
@ RS2_FORMAT_BGR8
Definition: rs_sensor.h:69
test-hdr-long.exposure_range
exposure_range
Definition: test-hdr-long.py:22
RS2_FRAME_METADATA_INPUT_HEIGHT
@ RS2_FRAME_METADATA_INPUT_HEIGHT
Definition: rs_frame.h:73
RS2_OPTION_SEQUENCE_SIZE
@ RS2_OPTION_SEQUENCE_SIZE
Definition: rs_option.h:107
profile
Definition: unit-tests-common.h:58
librealsense::device::map_supported_color_formats
std::vector< rs2_format > map_supported_color_formats(rs2_format source_format)
Definition: device.cpp:180
librealsense::extrinsics_graph::lock
extrinsics_lock lock()
Definition: environment.cpp:21
realdds::topics::control::hwm::key::opcode
const std::string opcode
rs_internal.h
Exposes RealSense internal functionality for C compilers.
LOG_ERROR
#define LOG_ERROR(...)
Definition: easyloggingpp.h:73
librealsense::d400_depth_sensor::close
void close() override
Definition: d400-device.cpp:211
fourcc.h
librealsense::RS2_FRAME_METADATA_HW_TYPE
@ RS2_FRAME_METADATA_HW_TYPE
Definition: frame-additional-data.h:22
librealsense::platform::uvc_header_mipi::frame_counter
uint32_t frame_counter
Definition: platform/uvc-device.h:73
librealsense::ds::DS5_ERROR_REPORTING
const uint8_t DS5_ERROR_REPORTING
Definition: ds-private.h:54
RS2_OPTION_ENABLE_AUTO_WHITE_BALANCE
@ RS2_OPTION_ENABLE_AUTO_WHITE_BALANCE
Definition: rs_option.h:39
RS2_OPTION_HDR_ENABLED
@ RS2_OPTION_HDR_ENABLED
Definition: rs_option.h:105
librealsense::ds::I2C_IMU_BMI085_ID_ACC
const uint8_t I2C_IMU_BMI085_ID_ACC
Definition: ds-private.h:536
librealsense::d400_device
Definition: d400-device.h:26


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