ds5-private.h
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2015 Intel Corporation. All Rights Reserved.
3 
4 #pragma once
5 
6 #include "backend.h"
7 #include "types.h"
9 
10 #include <map>
11 #include <iomanip>
12 #include <string>
13 
14 //#define DEBUG_THERMAL_LOOP
15 #ifdef DEBUG_THERMAL_LOOP
16 #define LOG_DEBUG_THERMAL_LOOP(...) do { CLOG(WARNING ,"librealsense") << __VA_ARGS__; } while(false)
17 #else
18 #define LOG_DEBUG_THERMAL_LOOP(...)
19 #endif //DEBUG_THERMAL_LOOP
20 
21 namespace librealsense
22 {
23  namespace ds
24  {
25  const uint16_t RS400_PID = 0x0ad1; // PSR
26  const uint16_t RS410_PID = 0x0ad2; // ASR
27  const uint16_t RS415_PID = 0x0ad3; // ASRC
28  const uint16_t RS430_PID = 0x0ad4; // AWG
29  const uint16_t RS430_MM_PID = 0x0ad5; // AWGT
30  const uint16_t RS_USB2_PID = 0x0ad6; // USB2
31  const uint16_t RS_RECOVERY_PID = 0x0adb;
33  const uint16_t RS400_IMU_PID = 0x0af2; // IMU
34  const uint16_t RS420_PID = 0x0af6; // PWG
35  const uint16_t RS420_MM_PID = 0x0afe; // PWGT
36  const uint16_t RS410_MM_PID = 0x0aff; // ASRT
37  const uint16_t RS400_MM_PID = 0x0b00; // PSR
38  const uint16_t RS430_MM_RGB_PID = 0x0b01; // AWGCT
39  const uint16_t RS460_PID = 0x0b03; // DS5U
40  const uint16_t RS435_RGB_PID = 0x0b07; // AWGC
41  const uint16_t RS405U_PID = 0x0b0c; // DS5U
42  const uint16_t RS435I_PID = 0x0b3a; // D435i
43  const uint16_t RS416_PID = 0x0b49; // F416
44  const uint16_t RS430I_PID = 0x0b4b; // D430i
45  const uint16_t RS465_PID = 0x0b4d; // D465
46  const uint16_t RS416_RGB_PID = 0x0B52; // F416 RGB
47  const uint16_t RS405_PID = 0x0B5B; // D405
48  const uint16_t RS455_PID = 0x0B5C; // D455
49 
50  // DS5 depth XU identifiers
53  const uint8_t DS5_EXPOSURE = 3;
61  const uint8_t DS5_LED_PWR = 0xE;
63 
64  // Devices supported by the current version
65  static const std::set<std::uint16_t> rs400_sku_pid = {
88  };
89 
90  static const std::set<std::uint16_t> multi_sensors_pid = {
101  };
102 
103  static const std::set<std::uint16_t> hid_sensors_pid = {
108  };
109 
110  static const std::set<std::uint16_t> hid_bmi_055_pid = {
114  };
115 
116  static const std::set<std::uint16_t> hid_bmi_085_pid = {
117  RS465_PID
118  };
119 
120  static const std::set<std::uint16_t> fisheye_pid = {
126  };
127 
128  static const std::map<std::uint16_t, std::string> rs400_sku_names = {
129  { RS400_PID, "Intel RealSense D400"},
130  { RS410_PID, "Intel RealSense D410"},
131  { RS415_PID, "Intel RealSense D415"},
132  { RS430_PID, "Intel RealSense D430"},
133  { RS430_MM_PID, "Intel RealSense D430 with Tracking Module"},
134  { RS_USB2_PID, "Intel RealSense USB2" },
135  { RS_RECOVERY_PID, "Intel RealSense D4xx Recovery"},
136  { RS_USB2_RECOVERY_PID, "Intel RealSense USB2 D4xx Recovery"},
137  { RS400_IMU_PID, "Intel RealSense IMU" },
138  { RS420_PID, "Intel RealSense D420"},
139  { RS420_MM_PID, "Intel RealSense D420 with Tracking Module"},
140  { RS410_MM_PID, "Intel RealSense D410 with Tracking Module"},
141  { RS400_MM_PID, "Intel RealSense D400 with Tracking Module"},
142  { RS430_MM_RGB_PID, "Intel RealSense D430 with Tracking and RGB Modules"},
143  { RS460_PID, "Intel RealSense D460" },
144  { RS435_RGB_PID, "Intel RealSense D435"},
145  { RS405U_PID, "Intel RealSense DS5U" },
146  { RS435I_PID, "Intel RealSense D435I" },
147  { RS416_PID, "Intel RealSense F416"},
148  { RS430I_PID, "Intel RealSense D430I"},
149  { RS465_PID, "Intel RealSense D465" },
150  { RS416_RGB_PID, "Intel RealSense F416 with RGB Module"},
151  { RS405_PID, "Intel RealSense D405" },
152  { RS455_PID, "Intel RealSense D455" },
153  };
154 
155  // DS5 fisheye XU identifiers
157 
158  // subdevice[h] unit[fw], node[h] guid[fw]
160  { 0xC9606CCB, 0x594C, 0x4D25,{ 0xaf, 0x47, 0xcc, 0xc4, 0x96, 0x43, 0x59, 0x95 } } };
161 
163  { 0xf6c3c3d1, 0x5cde, 0x4477,{ 0xad, 0xf0, 0x41, 0x33, 0xf5, 0x8d, 0xa6, 0xf4 } } };
164 
165  const int REGISTER_CLOCK_0 = 0x0001613c;
166 
167  const uint32_t FLASH_SIZE = 0x00200000;
168  const uint32_t FLASH_SECTOR_SIZE = 0x1000;
171  const uint32_t FLASH_INFO_HEADER_OFFSET = 0x001FFF00;
172 
173  flash_info get_flash_info(const std::vector<uint8_t>& flash_buffer);
174 
176  {
177  MRD = 0x01, // Read Register
178  FRB = 0x09, // Read from flash
179  FWB = 0x0a, // Write to flash <Parameter1 Name="StartIndex"> <Parameter2 Name="Size">
180  FES = 0x0b, // Erase flash sector <Parameter1 Name="Sector Index"> <Parameter2 Name="Number of Sectors">
181  FEF = 0x0c, // Erase flash full <Parameter1 Name="0xACE">
182  FSRU = 0x0d, // Flash status register unlock
183  FPLOCK = 0x0e, // Permanent lock on lower Quarter region of the flash
184  GLD = 0x0f, // FW logs
185  GVD = 0x10, // camera details
186  GETINTCAL = 0x15, // Read calibration table
187  SETINTCAL = 0x16, // Set Internal sub calibration table
188  LOADINTCAL = 0x1D, // Get Internal sub calibration table
189  DFU = 0x1E, // Enter to FW update mode
190  HWRST = 0x20, // hardware reset
191  OBW = 0x29, // OVT bypass write
192  SET_ADV = 0x2B, // set advanced mode control
193  GET_ADV = 0x2C, // get advanced mode control
194  EN_ADV = 0x2D, // enable advanced mode
195  UAMG = 0X30, // get advanced mode status
196  PFD = 0x3b, // Disable power features <Parameter1 Name="0 - Disable, 1 - Enable" />
197  SETAEROI = 0x44, // set auto-exposure region of interest
198  GETAEROI = 0x45, // get auto-exposure region of interest
199  MMER = 0x4F, // MM EEPROM read ( from DS5 cache )
200  CALIBRECALC = 0x51, // Calibration recalc and update on the fly
201  GET_EXTRINSICS = 0x53, // get extrinsics
202  CAL_RESTORE_DFLT= 0x61, // Reset Depth/RGB calibration to factory settings
203  SETINTCALNEW = 0x62, // Set Internal sub calibration table
204  SET_CAM_SYNC = 0x69, // set Inter-cam HW sync mode [0-default, 1-master, 2-slave]
205  GET_CAM_SYNC = 0x6A, // fet Inter-cam HW sync mode
206  SETRGBAEROI = 0x75, // set RGB auto-exposure region of interest
207  GETRGBAEROI = 0x76, // get RGB auto-exposure region of interest
208  SET_PWM_ON_OFF = 0x77, // set emitter on and off mode
209  GET_PWM_ON_OFF = 0x78, // get emitter on and off mode
210  SETSUBPRESET = 0x7B, // Download sub-preset
211  GETSUBPRESET = 0x7C, // Upload the current sub-preset
212  GETSUBPRESETID = 0x7D, // Retrieve sub-preset's name
213  RECPARAMSGET = 0x7E, // Retrieve depth calibration table in new format (fw >= 5.11.12.100)
214  LASERONCONST = 0x7F, // Enable Laser On constantly (GS SKU Only)
215  AUTO_CALIB = 0x80 // auto calibration commands
216  };
217 
218  #define TOSTRING(arg) #arg
219  #define VAR_ARG_STR(x) TOSTRING(x)
220  #define ENUM2STR(x) case(x):return VAR_ARG_STR(x);
221 
223  {
224  switch(state)
225  {
226  ENUM2STR(GLD);
227  ENUM2STR(GVD);
229  ENUM2STR(OBW);
230  ENUM2STR(SET_ADV);
231  ENUM2STR(GET_ADV);
232  ENUM2STR(EN_ADV);
233  ENUM2STR(UAMG);
236  ENUM2STR(MMER);
247  default:
248  return (to_string() << "Unrecognized FW command " << state);
249  }
250  }
251 
252  const int etDepthTableControl = 9; // Identifier of the depth table control
253 
255  {
256  GET_VAL = 0,
257  GET_MIN = 1,
258  GET_MAX = 2,
259  };
260 
262  {
267  INTERCAM_SYNC_MAX = 260 // 4-258 are for Genlock with burst count of 1-255 frames for each trigger.
268  // 259 for Sending two frame - First with laser ON, and the other with laser OFF.
269  // 260 for Sending two frame - First with laser OFF, and the other with laser ON.
270  };
271 
272  enum class d400_caps : uint16_t
273  {
274  CAP_UNDEFINED = 0,
275  CAP_ACTIVE_PROJECTOR = (1u << 0), //
276  CAP_RGB_SENSOR = (1u << 1), // Dedicated RGB sensor
277  CAP_FISHEYE_SENSOR = (1u << 2), // TM1
278  CAP_IMU_SENSOR = (1u << 3),
279  CAP_GLOBAL_SHUTTER = (1u << 4),
280  CAP_ROLLING_SHUTTER = (1u << 5),
281  CAP_BMI_055 = (1u << 6),
282  CAP_BMI_085 = (1u << 7),
283  CAP_MAX
284  };
285 
286  static const std::map<d400_caps, std::string> d400_capabilities_names = {
287  { d400_caps::CAP_UNDEFINED, "Undefined" },
288  { d400_caps::CAP_ACTIVE_PROJECTOR, "Active Projector" },
289  { d400_caps::CAP_RGB_SENSOR, "RGB Sensor" },
290  { d400_caps::CAP_FISHEYE_SENSOR, "Fisheye Sensor" },
291  { d400_caps::CAP_IMU_SENSOR, "IMU Sensor" },
292  { d400_caps::CAP_GLOBAL_SHUTTER, "Global Shutter" },
293  { d400_caps::CAP_ROLLING_SHUTTER, "Rolling Shutter" },
294  { d400_caps::CAP_BMI_055, "IMU BMI_055" },
295  { d400_caps::CAP_BMI_085, "IMU BMI_085" }
296  };
297 
298  inline d400_caps operator &(const d400_caps lhs, const d400_caps rhs)
299  {
300  return static_cast<d400_caps>(static_cast<uint32_t>(lhs) & static_cast<uint32_t>(rhs));
301  }
302 
303  inline d400_caps operator |(const d400_caps lhs, const d400_caps rhs)
304  {
305  return static_cast<d400_caps>(static_cast<uint32_t>(lhs) | static_cast<uint32_t>(rhs));
306  }
307 
309  {
310  return lhs = lhs | rhs;
311  }
312 
314  {
315  return !!(static_cast<uint8_t>(l) & static_cast<uint8_t>(r));
316  }
317 
318  inline std::ostream& operator <<(std::ostream& stream, const d400_caps& cap)
319  {
324  {
325  if (i==(i&cap))
326  stream << d400_capabilities_names.at(i) << "/";
327  }
328  return stream;
329  }
330 
331  const std::string DEPTH_STEREO = "Stereo Module";
332 
333 #pragma pack(push, 1)
335  {
336  big_endian<uint16_t> version; // major.minor. Big-endian
337  uint16_t table_type; // ctCalibration
338  uint32_t table_size; // full size including: TOC header + TOC + actual tables
339  uint32_t param; // This field content is defined ny table type
340  uint32_t crc32; // crc of all the actual table data excluding header/CRC
341  };
342 
343  enum ds5_rect_resolutions : unsigned short
344  {
358  // Resolutions for DS5U
363  };
364 
366  {
368  float3x3 intrinsic_left; // left camera intrinsic data, normilized
369  float3x3 intrinsic_right; // right camera intrinsic data, normilized
370  float3x3 world2left_rot; // the inverse rotation of the left camera
371  float3x3 world2right_rot; // the inverse rotation of the right camera
372  float baseline; // the baseline between the cameras in mm units
373  uint32_t brown_model; // Distortion model: 0 - DS distorion model, 1 - Brown model
374  uint8_t reserved1[88];
376  uint8_t reserved2[64];
377  };
378 
380  {
383  float fx;
384  float fy;
385  float ppx;
386  float ppy;
387  };
388 #pragma pack(pop)
389 
390  template<class T>
391  const T* check_calib(const std::vector<uint8_t>& raw_data)
392  {
393  using namespace std;
394 
395  auto table = reinterpret_cast<const T*>(raw_data.data());
396  auto header = reinterpret_cast<const table_header*>(raw_data.data());
397  if(raw_data.size() < sizeof(table_header))
398  {
399  throw invalid_value_exception(to_string() << "Calibration data invald, buffer too small : expected " << sizeof(table_header) << " , actual: " << raw_data.size());
400  }
401  // verify the parsed table
402  if (table->header.crc32 != calc_crc32(raw_data.data() + sizeof(table_header), raw_data.size() - sizeof(table_header)))
403  {
404  throw invalid_value_exception("Calibration data CRC error, parsing aborted!");
405  }
406  LOG_DEBUG("Loaded Valid Table: version [mjr.mnr]: 0x" <<
407  hex << setfill('0') << setw(4) << header->version << dec
408  << ", type " << header->table_type << ", size " << header->table_size
409  << ", CRC: " << hex << header->crc32);
410  return table;
411  }
412 
413 #pragma pack(push, 1)
414 
416  {
420  float3x3 rotation; // the fisheye rotation matrix
421  float3 translation; // the fisheye translation vector
422  };
423 
425  {
428  };
429 
431  {
432  float bias[3];
433  float scale[3];
434  };
435 
436  // Note that the intrinsic definition follows rs2_motion_device_intrinsic with different data layout
438  {
443  };
444 
446  {
448  float intrinsics_model; // 1 - Brown, 2 - FOV, 3 - Kannala Brandt
449  float3x3 intrinsic; // FishEye intrinsic matrix, normalize by [-1 1]
450  float distortion[5]; // FishEye forward distortion parameters, F-theta model
451  extrinsics_table fisheye_to_imu; // FishEye rotation matrix and translation vector in IMU CS
452  uint8_t reserved[28];
453  };
454 
456 
458  {
460  float rmax;
464  uint8_t reserved[64];
465  };
466 
468 
470  {
472  uint8_t serial_num[8]; // 2 bytes reserved + 6 data (0000xxxxxxxxxxxx)
473  uint8_t optic_module_mm[4];
474  uint8_t ta[10];
475  uint32_t board_num; // SKU id
477  uint8_t reserved[34]; // Align to 64 byte ???
478  };
479 
480  constexpr size_t tm1_module_info_size = sizeof(tm1_module_info);
481 
483  {
485  float calibration_model_flag; // 1 - Brown, 2 - FOV, 3 - Kannala Brandt ???????
487  float temperature;
488  uint8_t reserved[20];
489  };
490 
491  constexpr size_t tm1_calib_model_size = sizeof(tm1_calib_model);
492 
494  {
496  uint8_t serial_num[8]; // 2 bytes reserved + 6 data 12 digits in (0000xxxxxxxxxxxx) format
497  uint8_t reserved[8];
498  };
499 
501 
503  {
508  };
509 
511 
512  // TM1 ver 0.51
513  struct tm1_eeprom
514  {
518  };
519 
520  constexpr size_t tm1_eeprom_size = sizeof(tm1_eeprom);
521 
523  {
526  };
527 
529  {
533  uint8_t reserved[2];
534  extrinsics_table depth_to_imu; // The extrinsic parameters of IMU persented in Depth sensor's CS
537  uint8_t reserved1[96];
538  };
539 
541 
543  {
547  };
548 
549  constexpr size_t dm_v2_calib_info_size = sizeof(dm_v2_calib_info);
550 
551  // Depth Module V2 IMU EEPROM ver 0.52
553  {
556  };
557 
558  constexpr size_t dm_v2_eeprom_size = sizeof(dm_v2_eeprom);
559 
563  };
564 
565  constexpr size_t eeprom_imu_table_size = sizeof(eeprom_imu_table);
566 
568  {
569  dm_v2_eeprom_id = 0x0101, // The pack alignment is Big-endian
570  tm1_eeprom_id = 0x0002,
571  l500_eeprom_id = 0x0105
572  };
573 
575  {
581  };
582 
584  {
586  // RGB Intrinsic
587  float3x3 intrinsic; // normalized by [-1 1]
588  float distortion[5]; // RGB forward distortion coefficients, Brown model
589  // RGB Extrinsic
590  float3 rotation; // RGB rotation angles (Rodrigues)
591  float3 translation; // RGB translation vector, mm
592  // RGB Projection
593  float projection[12]; // Projection matrix from depth to RGB [3 X 4]
594  uint16_t calib_width; // original calibrated resolution
596  // RGB Rectification Coefficients
597  float3x3 intrinsic_matrix_rect; // RGB intrinsic matrix after rectification
598  float3x3 rotation_matrix_rect; // Rotation matrix for rectification of RGB
599  float3 translation_rect; // Translation vector for rectification
600  uint8_t reserved[24];
601  };
602 
603 
605  {
607 
608  for (int i = 0; i < 3; i++)
609  {
610  for (int j = 0; j < 3; j++)
611  result.data[i][j] = data.sensitivity(i,j);
612 
613  result.data[i][3] = data.bias[i];
614  result.bias_variances[i] = data.bias_variances[i];
615  result.noise_variances[i] = data.noise_variances[i];
616  }
617  return result;
618  }
619 
620 #pragma pack(pop)
621 
623  {
624  // Keep sorted
634  rgb_sensor = 174,
635  imu_sensor = 178,
637  };
638 
641 
643  {
644  // Keep sorted
646  };
647 
649  {
657  max_id = -1
658  };
659 
661  {
662  uint16_t version; // major.minor
669  std::map<calibration_table_id, bool> data_present;
670 
671  ds5_calibration() : version(0), left_imager_intrinsic({}), right_imager_intrinsic({}),
672  left_imager_extrinsic({}), right_imager_extrinsic({}), depth_extrinsic({})
673  {
674  for (auto i = 0; i < max_ds5_rect_resolutions; i++)
675  depth_intrinsic[i] = {};
676  data_present.emplace(coefficients_table_id, false);
677  data_present.emplace(depth_calibration_id, false);
678  data_present.emplace(rgb_calibration_id, false);
679  data_present.emplace(fisheye_calibration_id, false);
680  data_present.emplace(imu_calibration_id, false);
681  data_present.emplace(lens_shading_id, false);
682  data_present.emplace(projector_id, false);
683  }
684  };
685 
686  static std::map< ds5_rect_resolutions, int2> resolutions_list = {
687  { res_320_240,{ 320, 240 } },
688  { res_424_240,{ 424, 240 } },
689  { res_480_270,{ 480, 270 } },
690  { res_640_360,{ 640, 360 } },
691  { res_640_400,{ 640, 400 } },
692  { res_640_480,{ 640, 480 } },
693  { res_848_480,{ 848, 480 } },
694  { res_960_540,{ 960, 540 } },
695  { res_1280_720,{ 1280, 720 } },
696  { res_1280_800,{ 1280, 800 } },
697  { res_1920_1080,{ 1920, 1080 } },
698  //Resolutions for DS5U
699  { res_576_576,{ 576, 576 } },
700  { res_720_720,{ 720, 720 } },
701  { res_1152_1152,{ 1152, 1152 } },
702  };
703 
704 
706 
707  bool try_get_intrinsic_by_resolution_new(const std::vector<uint8_t>& raw_data,
708  uint32_t width, uint32_t height, rs2_intrinsics* result);
709 
710  rs2_intrinsics get_intrinsic_by_resolution(const std::vector<uint8_t>& raw_data, calibration_table_id table_id, uint32_t width, uint32_t height);
711  rs2_intrinsics get_intrinsic_by_resolution_coefficients_table(const std::vector<uint8_t>& raw_data, uint32_t width, uint32_t height);
712  rs2_intrinsics get_intrinsic_fisheye_table(const std::vector<uint8_t>& raw_data, uint32_t width, uint32_t height);
713  pose get_fisheye_extrinsics_data(const std::vector<uint8_t>& raw_data);
714  pose get_color_stream_extrinsic(const std::vector<uint8_t>& raw_data);
715 
716  bool try_fetch_usb_device(std::vector<platform::usb_device_info>& devices,
718 
719 
721  {
722  success = 0,
748  };
749 
750  // Elaborate FW XU report. The reports may be consequently extended for PU/CTL/ISP
751  const std::map< uint8_t, std::string> ds5_fw_error_report = {
752  { success, "Success" },
753  { hot_laser_power_reduce, "Laser hot - power reduce" },
754  { hot_laser_disable, "Laser hot - disabled" },
755  { flag_B_laser_disable, "Flag B - laser disabled" },
756  { stereo_module_not_connected, "Stereo Module is not connected" },
757  { eeprom_corrupted, "EEPROM corrupted" },
758  { calibration_corrupted, "Calibration corrupted" },
759  { mm_upd_fail, "Motion Module update failed" },
760  { isp_upd_fail, "ISP update failed" },
761  { mm_force_pause, "Motion Module force pause" },
762  { mm_failure, "Motion Module failure" },
763  { usb_scp_overflow, "USB SCP overflow" },
764  { usb_rec_overflow, "USB REC overflow" },
765  { usb_cam_overflow, "USB CAM overflow" },
766  { mipi_left_error, "Left MIPI error" },
767  { mipi_right_error, "Right MIPI error" },
768  { mipi_rt_error, "RT MIPI error" },
769  { mipi_fe_error, "FishEye MIPI error" },
770  { i2c_cfg_left_error, "Left IC2 Config error" },
771  { i2c_cfg_right_error, "Right IC2 Config error" },
772  { i2c_cfg_rt_error, "RT IC2 Config error" },
773  { i2c_cfg_fe_error, "FishEye IC2 Config error" },
774  { stream_not_start_z, "Depth stream start failure" },
775  { stream_not_start_y, "IR stream start failure" },
776  { stream_not_start_cam, "Camera stream start failure" },
777  { rec_error, "REC error" },
778  };
779 
780  std::vector<platform::uvc_device_info> filter_device_by_capability(const std::vector<platform::uvc_device_info>& devices, d400_caps caps);
781 
782  // subpreset pattern used in firmware versions that do not support subpreset ID
783  const std::vector<uint8_t> alternating_emitter_pattern_with_name{ 0x19, 0,
784  0x41, 0x6c, 0x74, 0x65, 0x72, 0x6e, 0x61, 0x74, 0x69, 0x6e, 0x67, 0x5f, 0x45, 0x6d, 0x69, 0x74, 0x74, 0x65, 0x72, 0,
785  0, 0x2, 0, 0x5, 0, 0x1, 0x1, 0, 0, 0, 0, 0, 0, 0, 0x5, 0, 0x1, 0x1, 0, 0, 0, 0x1, 0, 0, 0 };
786 
787  // subpreset ID for the alternating emitter subpreset as const
788  // in order to permit the query of this option to check if the current subpreset ID
789  // is the alternating emitter ID
791 
792  const std::vector<uint8_t> alternating_emitter_pattern { 0x5, ALTERNATING_EMITTER_SUBPRESET_ID, 0, 0, 0x2,
793  0x4, 0x1, 0, 0x1, 0, 0, 0, 0, 0,
794  0x4, 0x1, 0, 0x1, 0, 0x1, 0, 0, 0 };
795 
796  } // librealsense::ds
797 } // namespace librealsense
rs2_intrinsics get_intrinsic_by_resolution_coefficients_table(const std::vector< uint8_t > &raw_data, uint32_t width, uint32_t height)
Definition: ds5-private.cpp:24
const std::vector< uint8_t > alternating_emitter_pattern
Definition: ds5-private.h:792
const std::string DEPTH_STEREO
Definition: ds5-private.h:331
const int etDepthTableControl
Definition: ds5-private.h:252
constexpr size_t tm1_calibration_table_size
Definition: ds5-private.h:510
bool try_get_intrinsic_by_resolution_new(const vector< uint8_t > &raw_data, uint32_t width, uint32_t height, rs2_intrinsics *result)
const uint8_t I2C_IMU_BMI085_ID_ACC
Definition: ds5-private.h:640
const uint32_t FLASH_SIZE
Definition: ds5-private.h:167
const uint16_t RS_RECOVERY_PID
Definition: ds5-private.h:31
imu_calibration_table imu_calib_table
Definition: ds5-private.h:506
const uint8_t DS5_LASER_POWER
Definition: ds5-private.h:54
GLenum GLenum GLenum GLenum GLenum scale
Definition: glext.h:10806
rs2_intrinsics get_intrinsic_fisheye_table(const std::vector< uint8_t > &raw_data, uint32_t width, uint32_t height)
constexpr size_t tm1_serial_num_table_size
Definition: ds5-private.h:500
constexpr size_t tm1_eeprom_size
Definition: ds5-private.h:520
const uint8_t DS5_EXT_TRIGGER
Definition: ds5-private.h:57
const uint16_t RS415_PID
Definition: ds5-private.h:27
pose get_fisheye_extrinsics_data(const vector< uint8_t > &raw_data)
constexpr size_t imu_calibration_table_size
Definition: ds5-private.h:467
big_endian< uint16_t > version
Definition: ds5-private.h:336
static const std::map< d400_caps, std::string > d400_capabilities_names
Definition: ds5-private.h:286
bool operator&&(d400_caps l, d400_caps r)
Definition: ds5-private.h:313
static const std::set< std::uint16_t > hid_sensors_pid
Definition: ds5-private.h:103
const uint16_t RS460_PID
Definition: ds5-private.h:39
const uint16_t RS435_RGB_PID
Definition: ds5-private.h:40
const uint8_t DS5_HWMONITOR
Definition: ds5-private.h:51
static const std::set< std::uint16_t > fisheye_pid
Definition: ds5-private.h:120
constexpr size_t dm_v2_calib_info_size
Definition: ds5-private.h:549
const uint8_t DS5_ERROR_REPORTING
Definition: ds5-private.h:56
tm1_module_info module_info
Definition: ds5-private.h:516
unsigned short uint16_t
Definition: stdint.h:79
const uint8_t DS5_HARDWARE_PRESET
Definition: ds5-private.h:55
#define ENUM2STR(x)
Definition: ds5-private.h:220
static std::map< ds5_rect_resolutions, int2 > resolutions_list
Definition: ds5-private.h:686
GLsizei const GLchar *const * string
std_msgs::Header * header(M &m)
returns Header<M>::pointer(m);
const uint8_t DS5_LED_PWR
Definition: ds5-private.h:61
dm_v2_calib_info module_info
Definition: ds5-private.h:555
GLuint GLuint stream
Definition: glext.h:1790
unsigned char uint8_t
Definition: stdint.h:78
std::ostream & operator<<(std::ostream &stream, const d400_caps &cap)
Definition: ds5-private.h:318
const uint8_t DS5_THERMAL_COMPENSATION
Definition: ds5-private.h:62
ds5_rect_resolutions width_height_to_ds5_rect_resolutions(uint32_t width, uint32_t height)
Definition: ds5-private.cpp:14
GLenum cap
Definition: glext.h:8882
d400_caps & operator|=(d400_caps &lhs, d400_caps rhs)
Definition: ds5-private.h:308
const uint16_t RS400_IMU_PID
Definition: ds5-private.h:33
def info(name, value, persistent=False)
Definition: test.py:301
const uint16_t RS416_RGB_PID
Definition: ds5-private.h:46
const uint16_t RS405U_PID
Definition: ds5-private.h:41
tm1_serial_num_table serial_num_table
Definition: ds5-private.h:546
const uint16_t RS410_MM_PID
Definition: ds5-private.h:36
static const std::map< std::uint16_t, std::string > rs400_sku_names
Definition: ds5-private.h:128
const uint16_t RS455_PID
Definition: ds5-private.h:48
GLfloat bias
Definition: glext.h:7937
std::map< calibration_table_id, bool > data_present
Definition: ds5-private.h:669
const uint16_t RS410_PID
Definition: ds5-private.h:26
bool try_fetch_usb_device(std::vector< platform::usb_device_info > &devices, const platform::uvc_device_info &info, platform::usb_device_info &result)
GLdouble GLdouble r
static const std::set< std::uint16_t > rs400_sku_pid
Definition: ds5-private.h:65
fisheye_calibration_table fe_calibration
Definition: ds5-private.h:486
unsigned int uint32_t
Definition: stdint.h:80
constexpr size_t fisheye_calibration_table_size
Definition: ds5-private.h:455
devices
Definition: test-fg.py:9
const uint8_t ALTERNATING_EMITTER_SUBPRESET_ID
Definition: ds5-private.h:790
std::string fw_cmd2str(const fw_cmd state)
Definition: ds5-private.h:222
GLint GLsizei GLsizei height
dm_v2_calibration_table dm_v2_calib_table
Definition: ds5-private.h:545
const uint32_t FLASH_RW_TABLE_OF_CONTENT_OFFSET
Definition: ds5-private.h:169
const uint8_t FISHEYE_EXPOSURE
Definition: ds5-private.h:156
const int REGISTER_CLOCK_0
Definition: ds5-private.h:165
rs2_intrinsics get_intrinsic_by_resolution(const vector< uint8_t > &raw_data, calibration_table_id table_id, uint32_t width, uint32_t height)
GLint j
const uint16_t RS420_PID
Definition: ds5-private.h:34
const std::map< uint8_t, std::string > ds5_fw_error_report
Definition: ds5-private.h:751
const uint16_t RS_USB2_PID
Definition: ds5-private.h:30
constexpr size_t tm1_calib_model_size
Definition: ds5-private.h:491
const uint16_t RS_USB2_RECOVERY_PID
Definition: ds5-private.h:32
constexpr size_t dm_v2_calibration_table_size
Definition: ds5-private.h:540
const platform::extension_unit depth_xu
Definition: ds5-private.h:159
const uint8_t DS5_ENABLE_AUTO_EXPOSURE
Definition: ds5-private.h:60
const uint8_t DS5_EXPOSURE
Definition: ds5-private.h:53
const T * check_calib(const std::vector< uint8_t > &raw_data)
Definition: ds5-private.h:391
const uint16_t RS416_PID
Definition: ds5-private.h:43
constexpr size_t tm1_module_info_size
Definition: ds5-private.h:480
GLenum GLenum GLsizei void * table
d400_caps operator&(const d400_caps lhs, const d400_caps rhs)
Definition: ds5-private.h:298
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented...
Definition: rs_sensor.h:96
const uint16_t RS430_PID
Definition: ds5-private.h:28
const uint8_t I2C_IMU_BMI055_ID_ACC
Definition: ds5-private.h:639
const uint8_t DS5_ENABLE_AUTO_WHITE_BALANCE
Definition: ds5-private.h:59
const uint16_t RS420_MM_PID
Definition: ds5-private.h:35
const uint16_t RS435I_PID
Definition: ds5-private.h:42
d400_caps operator|(const d400_caps lhs, const d400_caps rhs)
Definition: ds5-private.h:303
const platform::extension_unit fisheye_xu
Definition: ds5-private.h:162
signed __int64 int64_t
Definition: stdint.h:89
const uint8_t DS5_DEPTH_EMITTER_ENABLED
Definition: ds5-private.h:52
const uint32_t FLASH_INFO_HEADER_OFFSET
Definition: ds5-private.h:171
Video stream intrinsics.
Definition: rs_types.h:58
const uint16_t RS430_MM_RGB_PID
Definition: ds5-private.h:38
static const std::set< std::uint16_t > hid_bmi_085_pid
Definition: ds5-private.h:116
const uint32_t FLASH_RO_TABLE_OF_CONTENT_OFFSET
Definition: ds5-private.h:170
Motion device intrinsics: scale, bias, and variances.
Definition: rs_types.h:103
int i
constexpr size_t dm_v2_eeprom_size
Definition: ds5-private.h:558
constexpr size_t eeprom_imu_table_size
Definition: ds5-private.h:565
tm1_calibration_table calibration_table
Definition: ds5-private.h:517
static const std::set< std::uint16_t > multi_sensors_pid
Definition: ds5-private.h:90
signed int int32_t
Definition: stdint.h:77
const uint32_t FLASH_SECTOR_SIZE
Definition: ds5-private.h:168
#define LOG_DEBUG(...)
Definition: src/types.h:239
std::vector< platform::uvc_device_info > filter_device_by_capability(const std::vector< platform::uvc_device_info > &devices, d400_caps caps)
static const std::set< std::uint16_t > hid_bmi_055_pid
Definition: ds5-private.h:110
pose get_color_stream_extrinsic(const std::vector< uint8_t > &raw_data)
const uint16_t RS465_PID
Definition: ds5-private.h:45
const uint16_t RS400_PID
Definition: ds5-private.h:25
GLuint64EXT * result
Definition: glext.h:10921
const uint16_t RS400_MM_PID
Definition: ds5-private.h:37
YYCODETYPE lhs
Definition: sqlite3.c:132469
const uint16_t RS430I_PID
Definition: ds5-private.h:44
const std::vector< uint8_t > alternating_emitter_pattern_with_name
Definition: ds5-private.h:783
Definition: parser.hpp:150
const uint8_t DS5_ASIC_AND_PROJECTOR_TEMPERATURES
Definition: ds5-private.h:58
GLint GLsizei width
const uint16_t RS430_MM_PID
Definition: ds5-private.h:29
uint32_t calc_crc32(const uint8_t *buf, size_t bufsize)
Calculate CRC code for arbitrary characters buffer.
Definition: types.cpp:803
const uint16_t RS405_PID
Definition: ds5-private.h:47
flash_info get_flash_info(const std::vector< uint8_t > &flash_buffer)
std::string to_string(T value)
rs2_motion_device_intrinsic create_motion_intrinsics(imu_intrinsic data)
Definition: ds5-private.h:604


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