ivcam-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 #ifndef LIBREALSENSE_IV_PRIVATE_H
6 #define LIBREALSENSE_IV_PRIVATE_H
7 
8 #include "uvc.h"
9 #include <mutex>
10 
11 namespace rsimpl {
12 namespace ivcam {
13 
14  const uvc::extension_unit depth_xu{ 1, 6, 1, { 0xA55751A1, 0xF3C5, 0x4A5E, { 0x8D, 0x5A, 0x68, 0x54, 0xB8, 0xFA, 0x27, 0x16 } } };
15 
17  {
18  float Rmax;
19  float Kc[3][3]; // [3x3]: intrinsic calibration matrix of the IR camera
20  float Distc[5]; // [1x5]: forward distortion parameters of the IR camera
21  float Invdistc[5]; // [1x5]: the inverse distortion parameters of the IR camera
22  float Pp[3][4]; // [3x4]: projection matrix
23  float Kp[3][3]; // [3x3]: intrinsic calibration matrix of the projector
24  float Rp[3][3]; // [3x3]: extrinsic calibration matrix of the projector
25  float Tp[3]; // [1x3]: translation vector of the projector
26  float Distp[5]; // [1x5]: forward distortion parameters of the projector
27  float Invdistp[5]; // [1x5]: inverse distortion parameters of the projector
28  float Pt[3][4]; // [3x4]: IR to RGB (texture mapping) image transformation matrix
29  float Kt[3][3];
30  float Rt[3][3];
31  float Tt[3];
32  float Distt[5]; // [1x5]: The inverse distortion parameters of the RGB camera
33  float Invdistt[5];
34  float QV[6];
35  };
36 
38  {
39  int uniqueNumber; //Should be 0xCAFECAFE in Calibration version 1 or later. In calibration version 0 this is zero.
40  int16_t TableValidation;
41  int16_t TableVersion;
43  };
44 
46  {
47  int enableMvR; // Send as IVCAMCommand::Param1
48  int enableLaser; // Send as IVCAMCommand::Param2
49  int16_t minMvR; // Copy into IVCAMCommand::data
50  int16_t maxMvR; // "
51  int16_t startMvR; // "
52  int16_t minLaser; // "
53  int16_t maxLaser; // "
54  int16_t startLaser; // "
55  uint16_t ARUpperTh; // Copy into IVCAMCommand::data if not -1
56  uint16_t ARLowerTh; // "
57  };
58 
59  enum class fw_cmd : uint8_t
60  {
61  GetMEMSTemp = 0x0A,
62  DebugFormat = 0x0B,
63  TimeStampEnable = 0x0C,
64  GetFWLastError = 0x0E,
65  HWReset = 0x28,
66  GVD = 0x3B,
67  GetCalibrationTable = 0x3D,
68  CheckI2cConnect = 0x4A,
69  CheckRGBConnect = 0x4B,
70  CheckDPTConnect = 0x4C,
71  GetIRTemp = 0x52,
72  GoToDFU = 0x80,
73  OnSuspendResume = 0x91,
74  GetWakeReason = 0x93,
75  GetWakeConfidence = 0x92,
76  SetAutoRange = 0xA6,
77  SetDefaultControls = 0xA6,
78  GetDefaultControls = 0xA7,
80  UpdateCalib = 0xBC,
81  BIST = 0xFF,
82  GetPowerGearState = 0xFF
83  };
84 
85  enum class FirmwareError : int32_t
86  {
87  FW_ACTIVE = 0,
95  FW_LD_ERR,
96  FW_PI_ERR,
98  FW_OAC_ERR,
129  };
130 
131  // Claim USB interface used for device
132  void claim_ivcam_interface(uvc::device & device);
133 
134  // Read device state
135  size_t prepare_usb_command(uint8_t * request, size_t & requestSize, uint32_t op, uint32_t p1 = 0, uint32_t p2 = 0, uint32_t p3 = 0, uint32_t p4 = 0, uint8_t * data = 0, size_t dataLength = 0);
136  void get_gvd(uvc::device & device, std::timed_mutex & mutex, size_t sz, char * gvd, int gvd_cmd = (int)fw_cmd::GVD);
137  void get_firmware_version_string(uvc::device & device, std::timed_mutex & mutex, std::string & version, int gvd_cmd = (int)fw_cmd::GVD, int offset = 0);
138  void get_module_serial_string(uvc::device & device, std::timed_mutex & mutex, std::string & serial, int offset);
139 
140  // Modify device state
141  void force_hardware_reset(uvc::device & device, std::timed_mutex & mutex);
142  void enable_timestamp(uvc::device & device, std::timed_mutex & mutex, bool colorEnable, bool depthEnable);
143  void set_auto_range(uvc::device & device, std::timed_mutex & mutex, int enableMvR, int16_t minMvR, int16_t maxMvR, int16_t startMvR, int enableLaser, int16_t minLaser, int16_t maxLaser, int16_t startLaser, int16_t ARUpperTH, int16_t ARLowerTH);
144 
145  // XU read/write
146  void get_laser_power(const uvc::device & device, uint8_t & laser_power);
147  void set_laser_power(uvc::device & device, uint8_t laser_power);
148  void get_accuracy(const uvc::device & device, uint8_t & accuracy);
149  void set_accuracy(uvc::device & device, uint8_t accuracy);
150  void get_motion_range(const uvc::device & device, uint8_t & motion_range);
151  void set_motion_range(uvc::device & device, uint8_t motion_range);
152  void get_filter_option(const uvc::device & device, uint8_t & filter_option);
153  void set_filter_option(uvc::device & device, uint8_t filter_option);
154  void get_confidence_threshold(const uvc::device & device, uint8_t & conf_thresh);
155  void set_confidence_threshold(uvc::device & device, uint8_t conf_thresh);
156 
157 } // rsimpl::ivcam
158 
159 namespace f200 {
160 
162  {
163  float LiguriaTemp;
164  float IRTemp;
165  float AmbientTemp;
166  };
167 
169  {
170  float IRThermalLoopEnable = 1; // enable the mechanism
171  float TimeOutA = 10000; // default time out
172  float TimeOutB = 0; // reserved
173  float TimeOutC = 0; // reserved
174  float TransitionTemp = 3; // celcius degrees, the transition temperatures to ignore and use offset;
175  float TempThreshold = 2; // celcius degrees, the temperatures delta that above should be fixed;
176  float HFOVsensitivity = 0.025f;
177  float FcxSlopeA = -0.003696988f; // the temperature model fc slope a from slope_hfcx = ref_fcx*a + b
178  float FcxSlopeB = 0.005809239f; // the temperature model fc slope b from slope_hfcx = ref_fcx*a + b
179  float FcxSlopeC = 0; // reserved
180  float FcxOffset = 0; // the temperature model fc offset
181  float UxSlopeA = -0.000210918f; // the temperature model ux slope a from slope_ux = ref_ux*a + ref_fcx*b
182  float UxSlopeB = 0.000034253955f; // the temperature model ux slope b from slope_ux = ref_ux*a + ref_fcx*b
183  float UxSlopeC = 0; // reserved
184  float UxOffset = 0; // the temperature model ux offset
185  float LiguriaTempWeight = 1; // the liguria temperature weight in the temperature delta calculations
186  float IrTempWeight = 0; // the Ir temperature weight in the temperature delta calculations
187  float AmbientTempWeight = 0; // reserved
188  float Param1 = 0; // reserved
189  float Param2 = 0; // reserved
190  float Param3 = 0; // reserved
191  float Param4 = 0; // reserved
192  float Param5 = 0; // reserved
193  };
194 
195  // Read calibration or device state
196  std::tuple<ivcam::camera_calib_params, f200::cam_temperature_data, thermal_loop_params> read_f200_calibration(uvc::device & device, std::timed_mutex & mutex);
197  float read_mems_temp(uvc::device & device, std::timed_mutex & mutex);
198  int read_ir_temp(uvc::device & device, std::timed_mutex & mutex);
199 
200  // Modify device state
201  void update_asic_coefficients(uvc::device & device, std::timed_mutex & mutex, const ivcam::camera_calib_params & compensated_params); // todo - Allow you to specify resolution
202 
203  void get_dynamic_fps(const uvc::device & device, uint8_t & dynamic_fps);
204  void set_dynamic_fps(uvc::device & device, uint8_t dynamic_fps);
205 
206 } // rsimpl::f200
207 
208 namespace sr300
209 {
210  // Read calibration or device state
211  ivcam::camera_calib_params read_sr300_calibration(uvc::device & device, std::timed_mutex & mutex);
212 } // rsimpl::sr300
213 } // namespace rsimpl
214 
215 #endif // IV_PRIVATE_H
void get_filter_option(const uvc::device &device, uint8_t &filter_option)
void update_asic_coefficients(uvc::device &device, std::timed_mutex &mutex, const ivcam::camera_calib_params &compensated_params)
void get_motion_range(const uvc::device &device, uint8_t &motion_range)
void get_laser_power(const uvc::device &device, uint8_t &laser_power)
void set_dynamic_fps(uvc::device &device, uint8_t dynamic_fps)
GLsizei const GLchar *const * string
Definition: glext.h:683
Definition: archive.h:12
void set_auto_range(uvc::device &device, std::timed_mutex &mutex, int enableMvR, int16_t minMvR, int16_t maxMvR, int16_t startMvR, int enableLaser, int16_t minLaser, int16_t maxLaser, int16_t startLaser, int16_t ARUpperTH, int16_t ARLowerTH)
void force_hardware_reset(uvc::device &device, std::timed_mutex &mutex)
int read_ir_temp(uvc::device &device, std::timed_mutex &mutex)
ivcam::camera_calib_params CalibrationParameters
Definition: ivcam-private.h:42
void set_confidence_threshold(uvc::device &device, uint8_t conf_thresh)
void get_confidence_threshold(const uvc::device &device, uint8_t &conf_thresh)
void set_laser_power(uvc::device &device, uint8_t laser_power)
void get_dynamic_fps(const uvc::device &device, uint8_t &dynamic_fps)
ivcam::camera_calib_params read_sr300_calibration(uvc::device &device, std::timed_mutex &mutex)
const uvc::extension_unit depth_xu
Definition: ivcam-private.h:14
void get_accuracy(const uvc::device &device, uint8_t &accuracy)
void get_module_serial_string(uvc::device &device, std::timed_mutex &mutex, std::string &serial, int offset)
GLint GLenum GLsizei GLsizei GLsizei GLint GLsizei const void * data
Definition: glext.h:223
GLintptr offset
Definition: glext.h:533
void set_filter_option(uvc::device &device, uint8_t filter_option)
void set_accuracy(uvc::device &device, uint8_t accuracy)
float read_mems_temp(uvc::device &device, std::timed_mutex &mutex)
void get_firmware_version_string(uvc::device &device, std::timed_mutex &mutex, std::string &version, int gvd_cmd, int offset)
std::tuple< ivcam::camera_calib_params, cam_temperature_data, thermal_loop_params > read_f200_calibration(uvc::device &device, std::timed_mutex &mutex)
void enable_timestamp(uvc::device &device, std::timed_mutex &mutex, bool colorEnable, bool depthEnable)
void get_gvd(uvc::device &device, std::timed_mutex &mutex, size_t sz, char *gvd, int gvd_cmd)
size_t prepare_usb_command(uint8_t *request, size_t &requestSize, uint32_t op, uint32_t p1, uint32_t p2, uint32_t p3, uint32_t p4, uint8_t *data, size_t dataLength)
void set_motion_range(uvc::device &device, uint8_t motion_range)
void claim_ivcam_interface(uvc::device &device)


librealsense
Author(s): Sergey Dorodnicov , Mark Horn , Reagan Lopez
autogenerated on Fri Mar 13 2020 03:16:17