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 |
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::string > | l500_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::string > | rs500_sku_names |
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.
Definition at line 262 of file l500-private.h.
| 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.
| auto librealsense::ivcam2::group_multiple_fw_calls | ( | synthetic_sensor & | s, |
| T | action | ||
| ) | -> decltype(action()) |
Definition at line 615 of file l500-private.h.
|
static |
Definition at line 181 of file ac-trigger.cpp.
|
static |
Definition at line 173 of file ac-trigger.cpp.
|
static |
Definition at line 1458 of file ac-trigger.cpp.
| void librealsense::ivcam2::read_fw_register | ( | hw_monitor & | hwm, |
| T * | preg, | ||
| int const | baseline_address | ||
| ) |
Definition at line 178 of file l500-private.h.
| 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 |
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.
| 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.
| const platform::extension_unit librealsense::ivcam2::depth_xu |
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 |
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.
|
static |
Definition at line 250 of file l500-private.h.