Classes | Namespaces | Enumerations | Functions | Variables
l500-private.h File Reference
#include "backend.h"
#include "types.h"
#include "option.h"
#include "core/extension.h"
#include "fw-update/fw-update-unsigned.h"
Include dependency graph for l500-private.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

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

Namespaces

 librealsense
 
 librealsense::ivcam2
 

Enumerations

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

Functions

rs2_extrinsics librealsense::ivcam2::get_color_stream_extrinsic (const std::vector< uint8_t > &raw_data)
 
flash_info librealsense::ivcam2::get_flash_info (const std::vector< uint8_t > &flash_buffer)
 
rs2_sensor_mode librealsense::ivcam2::get_resolution_from_width_height (int width, int height)
 
template<class T >
auto librealsense::ivcam2::group_multiple_fw_calls (synthetic_sensor &s, T action) -> decltype(action())
 
template<typename T >
void librealsense::ivcam2::read_fw_register (hw_monitor &hwm, T *preg, int const baseline_address)
 
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)
 
static std::vector< bytelibrealsense::ivcam2::read_fw_table_raw (const hw_monitor &hwm, int table_id, hwmon_response &response)
 
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)
 
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)
 

Variables

const platform::extension_unit librealsense::ivcam2::depth_xu
 
const uint32_t librealsense::ivcam2::FLASH_INFO_HEADER_OFFSET = 0x001FFF00
 
const uint32_t librealsense::ivcam2::FLASH_RO_TABLE_OF_CONTENT_OFFSET = 0x001FFD00
 
const uint32_t librealsense::ivcam2::FLASH_RW_TABLE_OF_CONTENT_OFFSET = 0x0017FE00
 
const uint32_t librealsense::ivcam2::FLASH_SECTOR_SIZE = 0x1000
 
const uint32_t librealsense::ivcam2::FLASH_SIZE = 0x00200000
 
const uint8_t librealsense::ivcam2::L500_DIGITAL_GAIN = 2
 
const uint8_t librealsense::ivcam2::L500_ERROR_REPORTING = 3
 
const std::map< uint8_t, std::stringlibrealsense::ivcam2::l500_fw_error_report
 
const uint8_t librealsense::ivcam2::L500_HWMONITOR = 1
 
const uint16_t librealsense::L500_PID = 0x0b0d
 
const uint16_t librealsense::L500_RECOVERY_PID = 0x0b55
 
const uint16_t librealsense::L500_USB2_RECOVERY_PID_OLD = 0x0adc
 
const uint16_t librealsense::ivcam2::L515_IMU_TABLE = 0x0243
 
const uint16_t librealsense::L515_PID = 0x0b64
 
const uint16_t librealsense::L515_PID_PRE_PRQ = 0x0b3d
 
const uint16_t librealsense::L535_PID = 0x0b68
 
const uint16_t librealsense::L535_RECOVERY_PID = 0x0B72
 
static const int MAX_NUM_OF_DEPTH_RESOLUTIONS = 5
 
static const int MAX_NUM_OF_RGB_RESOLUTIONS = 5
 
const int librealsense::ivcam2::REGISTER_CLOCK_0 = 0x9003021c
 
static const std::map< std::uint16_t, std::stringlibrealsense::ivcam2::rs500_sku_names
 

Variable Documentation

const int MAX_NUM_OF_DEPTH_RESOLUTIONS = 5
static

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

const int MAX_NUM_OF_RGB_RESOLUTIONS = 5
static

Definition at line 12 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:27