Classes | Enumerations | Functions | Variables
librealsense::ivcam2 Namespace Reference

Classes

struct  ac_depth_results
 
class  ac_trigger
 
struct  distortion
 
struct  extended_temperatures
 
class  freefall_option
 
class  hw_sync_option
 
struct  intrinsic_depth
 
struct  intrinsic_params
 
struct  intrinsic_per_resolution
 
struct  intrinsic_rgb
 
class  l500_temperature_options
 
class  l500_timestamp_reader
 
class  l500_timestamp_reader_from_metadata
 
class  nest_option
 
struct  orientation
 
struct  pinhole_camera_model
 
struct  pinhole_model
 
struct  resolutions_depth
 
struct  resolutions_rgb
 
struct  rgb_calibration_table
 
struct  rgb_common
 
struct  table_header
 
struct  temperatures
 

Enumerations

enum  fw_cmd : uint8_t {
  IRB = 0x03, MRD = 0x01, FRB = 0x09, FWB = 0x0A,
  FES = 0x0B, FEF = 0x0C, GLD = 0x0F, GVD = 0x10,
  DFU = 0x1E, HW_SYNC_EX_TRIGGER = 0x19, HW_RESET = 0x20, AMCSET = 0x2B,
  AMCGET = 0x2C, DELETE_TABLE = 0x2E, TPROC_TRB_THRSLD_SET = 0x35, TPROC_USB_GRAN_SET = 0x36,
  PFD = 0x3B, READ_TABLE = 0x43, WRITE_TABLE = 0x44, DPT_INTRINSICS_GET = 0x5A,
  TEMPERATURES_GET = 0x6A, DPT_INTRINSICS_FULL_GET = 0x7F, RGB_INTRINSIC_GET = 0x81, RGB_EXTRINSIC_GET = 0x82,
  FALL_DETECT_ENABLE = 0x9D, GET_SPECIAL_FRAME = 0xA0, UNIT_AGE_SET = 0x5B
}
 
enum  gvd_fields { is_camera_locked_offset = 6, fw_version_offset = 12, module_serial_offset = 60, module_asic_serial_offset = 74 }
 
enum  gvd_fields_size { module_serial_size = 4, module_asic_serial_size = 6 }
 
enum  l500_notifications_types {
  success = 0, depth_not_available, overflow_infrared, overflow_depth,
  overflow_confidence, depth_stream_hard_error, depth_stream_soft_error, temp_warning,
  temp_critical, DFU_error, fall_detected = 12, ld_alarm = 14,
  hard_error = 15, ld_alarm_hard_error = 16, pzr_vbias_exceed_limit = 17, eye_safety_general_critical_error = 18,
  eye_safety_stuck_at_ld_error = 19, eye_safety_stuck_at_mode_sign_error = 20, eye_safety_stuck_at_vbst_error = 21, eye_safety_stuck_at_msafe_error = 22,
  eye_safety_stuck_at_ldd_snubber_error = 23, eye_safety_stuck_at_flash_otp_error = 24
}
 

Functions

rs2_extrinsics get_color_stream_extrinsic (const std::vector< uint8_t > &raw_data)
 
flash_info get_flash_info (const std::vector< uint8_t > &flash_buffer)
 
rs2_sensor_mode get_resolution_from_width_height (int width, int height)
 
flash_structure get_ro_flash_structure (const uint32_t flash_version)
 
flash_structure get_rw_flash_structure (const uint32_t flash_version)
 
template<class T >
auto group_multiple_fw_calls (synthetic_sensor &s, T action) -> decltype(action())
 
static bool is_auto_trigger_default ()
 
static bool is_auto_trigger_possible ()
 
static bool is_special_frame (rs2::depth_frame const &f)
 
template<typename T >
void read_fw_register (hw_monitor &hwm, T *preg, int const baseline_address)
 
template<typename T >
void read_fw_table (hw_monitor &hwm, int table_id, T *ptable, table_header *pheader=nullptr, std::function< void() > init=nullptr)
 
static std::vector< byteread_fw_table_raw (const hw_monitor &hwm, int table_id, hwmon_response &response)
 
rs2_intrinsics read_intrinsics_from_camera (l500_device &dev, const rs2::stream_profile &profile)
 
bool try_fetch_usb_device (std::vector< platform::usb_device_info > &devices, const platform::uvc_device_info &info, platform::usb_device_info &result)
 
template<typename T >
void write_fw_table (hw_monitor &hwm, uint16_t const table_id, T const &table, uint16_t const version=0x0100)
 

Variables

const platform::extension_unit depth_xu
 
const uint32_t FLASH_INFO_HEADER_OFFSET = 0x001FFF00
 
const uint32_t FLASH_RO_TABLE_OF_CONTENT_OFFSET = 0x001FFD00
 
const uint32_t FLASH_RW_TABLE_OF_CONTENT_OFFSET = 0x0017FE00
 
const uint32_t FLASH_SECTOR_SIZE = 0x1000
 
const uint32_t FLASH_SIZE = 0x00200000
 
const uint8_t L500_DIGITAL_GAIN = 2
 
const uint8_t L500_ERROR_REPORTING = 3
 
const std::map< uint8_t, std::stringl500_fw_error_report
 
const uint8_t L500_HWMONITOR = 1
 
const uint16_t L515_IMU_TABLE = 0x0243
 
const int REGISTER_CLOCK_0 = 0x9003021c
 
static const std::map< std::uint16_t, std::stringrs500_sku_names
 

Enumeration Type Documentation

Enumerator
IRB 
MRD 
FRB 
FWB 
FES 
FEF 
GLD 
GVD 
DFU 
HW_SYNC_EX_TRIGGER 
HW_RESET 
AMCSET 
AMCGET 
DELETE_TABLE 
TPROC_TRB_THRSLD_SET 
TPROC_USB_GRAN_SET 
PFD 
READ_TABLE 
WRITE_TABLE 
DPT_INTRINSICS_GET 
TEMPERATURES_GET 
DPT_INTRINSICS_FULL_GET 
RGB_INTRINSIC_GET 
RGB_EXTRINSIC_GET 
FALL_DETECT_ENABLE 
GET_SPECIAL_FRAME 
UNIT_AGE_SET 

Definition at line 50 of file l500-private.h.

Enumerator
is_camera_locked_offset 
fw_version_offset 
module_serial_offset 
module_asic_serial_offset 

Definition at line 235 of file l500-private.h.

Enumerator
module_serial_size 
module_asic_serial_size 

Definition at line 243 of file l500-private.h.

Enumerator
success 
depth_not_available 
overflow_infrared 
overflow_depth 
overflow_confidence 
depth_stream_hard_error 
depth_stream_soft_error 
temp_warning 
temp_critical 
DFU_error 
fall_detected 
ld_alarm 
hard_error 
ld_alarm_hard_error 
pzr_vbias_exceed_limit 
eye_safety_general_critical_error 
eye_safety_stuck_at_ld_error 
eye_safety_stuck_at_mode_sign_error 
eye_safety_stuck_at_vbst_error 
eye_safety_stuck_at_msafe_error 
eye_safety_stuck_at_ldd_snubber_error 
eye_safety_stuck_at_flash_otp_error 

Definition at line 262 of file l500-private.h.

Function Documentation

rs2_extrinsics librealsense::ivcam2::get_color_stream_extrinsic ( const std::vector< uint8_t > &  raw_data)

Definition at line 29 of file l500-private.cpp.

flash_info librealsense::ivcam2::get_flash_info ( const std::vector< uint8_t > &  flash_buffer)

Definition at line 129 of file l500-private.cpp.

rs2_sensor_mode librealsense::ivcam2::get_resolution_from_width_height ( int  width,
int  height 
)

Definition at line 207 of file l500-private.cpp.

flash_structure librealsense::ivcam2::get_ro_flash_structure ( const uint32_t  flash_version)

Definition at line 118 of file l500-private.cpp.

flash_structure librealsense::ivcam2::get_rw_flash_structure ( const uint32_t  flash_version)

Definition at line 107 of file l500-private.cpp.

template<class T >
auto librealsense::ivcam2::group_multiple_fw_calls ( synthetic_sensor s,
action 
) -> decltype(action())

Definition at line 615 of file l500-private.h.

static bool librealsense::ivcam2::is_auto_trigger_default ( )
static

Definition at line 181 of file ac-trigger.cpp.

static bool librealsense::ivcam2::is_auto_trigger_possible ( )
static

Definition at line 173 of file ac-trigger.cpp.

static bool librealsense::ivcam2::is_special_frame ( rs2::depth_frame const &  f)
static

Definition at line 1458 of file ac-trigger.cpp.

template<typename T >
void librealsense::ivcam2::read_fw_register ( hw_monitor hwm,
T *  preg,
int const  baseline_address 
)

Definition at line 178 of file l500-private.h.

template<typename T >
void librealsense::ivcam2::read_fw_table ( hw_monitor hwm,
int  table_id,
T *  ptable,
table_header pheader = nullptr,
std::function< void() >  init = nullptr 
)

Definition at line 109 of file l500-private.h.

static std::vector< byte > librealsense::ivcam2::read_fw_table_raw ( const hw_monitor hwm,
int  table_id,
hwmon_response response 
)
static

Definition at line 95 of file l500-private.h.

rs2_intrinsics librealsense::ivcam2::read_intrinsics_from_camera ( l500_device dev,
const rs2::stream_profile profile 
)

Definition at line 933 of file ac-trigger.cpp.

bool librealsense::ivcam2::try_fetch_usb_device ( std::vector< platform::usb_device_info > &  devices,
const platform::uvc_device_info info,
platform::usb_device_info result 
)

Definition at line 41 of file l500-private.cpp.

template<typename T >
void librealsense::ivcam2::write_fw_table ( hw_monitor hwm,
uint16_t const  table_id,
T const &  table,
uint16_t const  version = 0x0100 
)

Definition at line 149 of file l500-private.h.

Variable Documentation

const platform::extension_unit librealsense::ivcam2::depth_xu
Initial value:
= { 0, 3, 2,
{ 0xC9606CCB, 0x594C, 0x4D25,{ 0xaf, 0x47, 0xcc, 0xc4, 0x96, 0x43, 0x59, 0x95 } } }

Definition at line 43 of file l500-private.h.

const uint32_t librealsense::ivcam2::FLASH_INFO_HEADER_OFFSET = 0x001FFF00

Definition at line 39 of file l500-private.h.

const uint32_t librealsense::ivcam2::FLASH_RO_TABLE_OF_CONTENT_OFFSET = 0x001FFD00

Definition at line 38 of file l500-private.h.

const uint32_t librealsense::ivcam2::FLASH_RW_TABLE_OF_CONTENT_OFFSET = 0x0017FE00

Definition at line 37 of file l500-private.h.

const uint32_t librealsense::ivcam2::FLASH_SECTOR_SIZE = 0x1000

Definition at line 35 of file l500-private.h.

const uint32_t librealsense::ivcam2::FLASH_SIZE = 0x00200000

Definition at line 34 of file l500-private.h.

const uint8_t librealsense::ivcam2::L500_DIGITAL_GAIN = 2

Definition at line 31 of file l500-private.h.

const uint8_t librealsense::ivcam2::L500_ERROR_REPORTING = 3

Definition at line 32 of file l500-private.h.

const std::map< uint8_t, std::string > librealsense::ivcam2::l500_fw_error_report
Initial value:
= {
{ success, "Success" },
{ depth_not_available, "Fatal error occur and device is unable \nto run depth stream" },
{ overflow_infrared, "Overflow occur on infrared stream" },
{ overflow_depth, "Overflow occur on depth stream" },
{ overflow_confidence, "Overflow occur on confidence stream" },
{ depth_stream_hard_error, "Receiver light saturation, stream stopped for 1 sec" },
{ depth_stream_soft_error, "Error that may be overcome in few sec. \nStream stoped. May be recoverable" },
{ temp_warning, "Warning, temperature close to critical" },
{ temp_critical, "Critical temperature reached" },
{ DFU_error, "DFU error" },
{ fall_detected, "Fall detected stream stopped" },
{ ld_alarm, "Fatal error occurred (14)" },
{ hard_error, "Fatal error occurred (15)" },
{ ld_alarm_hard_error, "Fatal error occurred (16)" },
{ pzr_vbias_exceed_limit, "Fatal error occurred (17)" },
{ eye_safety_general_critical_error, "Fatal error occurred (18)" },
{ eye_safety_stuck_at_ld_error, "Fatal error occurred (19)" },
{ eye_safety_stuck_at_mode_sign_error, "Fatal error occurred (20)" },
{ eye_safety_stuck_at_vbst_error, "Fatal error occurred (21)" },
{ eye_safety_stuck_at_msafe_error, "Fatal error occurred (22)" },
{ eye_safety_stuck_at_ldd_snubber_error, "Fatal error occurred (23)" },
{ eye_safety_stuck_at_flash_otp_error, "Fatal error occurred (24)" }
}

Definition at line 291 of file l500-private.h.

const uint8_t librealsense::ivcam2::L500_HWMONITOR = 1

Definition at line 30 of file l500-private.h.

const uint16_t librealsense::ivcam2::L515_IMU_TABLE = 0x0243

Definition at line 48 of file l500-private.h.

const int librealsense::ivcam2::REGISTER_CLOCK_0 = 0x9003021c

Definition at line 46 of file l500-private.h.

const std::map<std::uint16_t, std::string> librealsense::ivcam2::rs500_sku_names
static
Initial value:
= {
{ L500_RECOVERY_PID, "Intel RealSense L5xx Recovery"},
{ L535_RECOVERY_PID, "Intel RealSense L5xx Recovery"},
{ L500_USB2_RECOVERY_PID_OLD, "Intel RealSense L5xx Recovery"},
{ L500_PID, "Intel RealSense L500"},
{ L515_PID_PRE_PRQ, "Intel RealSense L515 (pre-PRQ)"},
{ L515_PID, "Intel RealSense L515"},
{ L535_PID, "Intel RealSense L535"},
}
const uint16_t L535_RECOVERY_PID
Definition: l500-private.h:18
const uint16_t L500_USB2_RECOVERY_PID_OLD
Definition: l500-private.h:19
const uint16_t L515_PID
Definition: l500-private.h:22
const uint16_t L535_PID
Definition: l500-private.h:23
const uint16_t L500_RECOVERY_PID
Definition: l500-private.h:17
const uint16_t L515_PID_PRE_PRQ
Definition: l500-private.h:21
const uint16_t L500_PID
Definition: l500-private.h:20

Definition at line 250 of file l500-private.h.



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