Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
librealsense::l500_device Class Referenceabstract

#include <l500-device.h>

Inheritance diagram for librealsense::l500_device:
Inheritance graph
[legend]

Public Member Functions

std::vector< uint8_tbackup_flash (update_progress_callback_ptr callback) override
 
virtual void configure_depth_options ()
 
std::shared_ptr< synthetic_sensorcreate_depth_device (std::shared_ptr< context > ctx, const std::vector< platform::uvc_device_info > &all_device_infos)
 
void create_snapshot (std::shared_ptr< debug_interface > &snapshot) const override
 
void enable_recording (std::function< void(const debug_interface &)> record_action) override
 
void enter_update_state () const override
 
virtual l500_color_sensorget_color_sensor ()=0
 
l500_depth_sensorget_depth_sensor ()
 
double get_device_time_ms () override
 
uvc_sensorget_raw_depth_sensor ()
 
synthetic_sensorget_synthetic_depth_sensor ()
 
ivcam2::extended_temperatures get_temperatures () const
 
void hardware_reset () override
 
 l500_device (std::shared_ptr< context > ctx, const platform::backend_device_group &group)
 
void notify_of_calibration_change (rs2_calibration_status status)
 
void register_calibration_change_callback (calibration_change_callback_ptr callback) override
 
std::vector< uint8_tsend_receive_raw_data (const std::vector< uint8_t > &input) override
 
void trigger_device_calibration (rs2_calibration_type) override
 
void update_flash (const std::vector< uint8_t > &image, update_progress_callback_ptr callback, int update_mode) override
 
void update_flash_internal (std::shared_ptr< hw_monitor > hwm, const std::vector< uint8_t > &image, std::vector< uint8_t > &flash_backup, update_progress_callback_ptr callback, int update_mode)
 
void update_flash_section (std::shared_ptr< hw_monitor > hwm, const std::vector< uint8_t > &image, uint32_t offset, uint32_t size, update_progress_callback_ptr callback, float continue_from, float ratio)
 
void update_section (std::shared_ptr< hw_monitor > hwm, const std::vector< uint8_t > &merged_image, flash_section fs, uint32_t tables_size, update_progress_callback_ptr callback, float continue_from, float ratio)
 
- Public Member Functions inherited from librealsense::device
virtual bool compress_while_record () const override
 
virtual bool contradicts (const stream_profile_interface *a, const std::vector< stream_profile > &others) const override
 
virtual std::shared_ptr< matchercreate_matcher (const frame_holder &frame) const override
 
size_t find_sensor_idx (const sensor_interface &s) const
 
std::shared_ptr< contextget_context () const override
 
platform::backend_device_group get_device_data () const override
 
std::pair< uint32_t, rs2_extrinsicsget_extrinsics (const stream_interface &stream) const override
 
sensor_interfaceget_sensor (size_t subdevice) override
 
const sensor_interfaceget_sensor (size_t subdevice) const override
 
size_t get_sensors_count () const override
 
bool is_valid () const override
 
virtual void stop_activity () const
 
void tag_profiles (stream_profiles profiles) const override
 
virtual ~device ()
 
- Public Member Functions inherited from librealsense::device_interface
virtual std::vector< tagged_profileget_profiles_tags () const =0
 
virtual ~device_interface ()=default
 
- Public Member Functions inherited from librealsense::info_interface
virtual ~info_interface ()=default
 
- Public Member Functions inherited from librealsense::recordable< info_interface >
virtual ~recordable ()=default
 
- Public Member Functions inherited from librealsense::info_container
void create_snapshot (std::shared_ptr< info_interface > &snapshot) const override
 
void enable_recording (std::function< void(const info_interface &)> record_action) override
 
const std::stringget_info (rs2_camera_info info) const override
 
void register_info (rs2_camera_info info, const std::string &val)
 
bool supports_info (rs2_camera_info info) const override
 
void update (std::shared_ptr< extension_snapshot > ext) override
 
void update_info (rs2_camera_info info, const std::string &val)
 
- Public Member Functions inherited from librealsense::extension_snapshot
virtual ~extension_snapshot ()=default
 
- Public Member Functions inherited from librealsense::recordable< debug_interface >
virtual ~recordable ()=default
 
- Public Member Functions inherited from librealsense::global_time_interface
virtual void create_snapshot (std::shared_ptr< global_time_interface > &snapshot) const override
 
virtual void enable_recording (std::function< void(const global_time_interface &)> record_action) override
 
void enable_time_diff_keeper (bool is_enable)
 
 global_time_interface ()
 
 ~global_time_interface ()
 
- Public Member Functions inherited from librealsense::recordable< global_time_interface >
virtual ~recordable ()=default
 

Protected Member Functions

void force_hardware_reset () const
 
command get_firmware_logs_command () const
 
command get_flash_logs_command () const
 
void start_temperatures_reader ()
 
void stop_temperatures_reader ()
 
- Protected Member Functions inherited from librealsense::device
int add_sensor (const std::shared_ptr< sensor_interface > &sensor_base)
 
int assign_sensor (const std::shared_ptr< sensor_interface > &sensor_base, uint8_t idx)
 
 device (std::shared_ptr< context > ctx, const platform::backend_device_group group, bool device_changed_notifications=false)
 
std::vector< rs2_formatmap_supported_color_formats (rs2_format source_format)
 
void register_stream_to_extrinsic_group (const stream_interface &stream, uint32_t groupd_index)
 

Protected Attributes

std::vector< rs2_option_advanced_options
 
std::shared_ptr< ivcam2::ac_trigger_autocal
 
lazy< ivcam2::intrinsic_depth_calib_table
 
std::vector< calibration_change_callback_ptr_calibration_change_callbacks
 
std::shared_ptr< stream_interface_confidence_stream
 
uint8_t _depth_device_idx
 
std::shared_ptr< stream_interface_depth_stream
 
firmware_version _fw_version
 
std::atomic_bool _have_temperatures { false }
 
std::shared_ptr< hw_monitor_hw_monitor
 
std::shared_ptr< stream_interface_ir_stream
 
bool _is_locked = true
 
std::atomic_bool _keep_reading_temperature { false }
 
std::shared_ptr< polling_error_handler_polling_error_handler
 
std::mutex _temperature_mutex
 
std::thread _temperature_reader
 
ivcam2::extended_temperatures _temperatures
 
platform::usb_spec _usb_mode
 
- Protected Attributes inherited from librealsense::device
std::map< int, std::pair< uint32_t, std::shared_ptr< const stream_interface > > > _extrinsics
 
- Protected Attributes inherited from librealsense::global_time_interface
std::shared_ptr< time_diff_keeper_tf_keeper
 

Friends

class l500_depth_sensor
 

Detailed Description

Definition at line 26 of file l500-device.h.

Constructor & Destructor Documentation

librealsense::l500_device::l500_device ( std::shared_ptr< context ctx,
const platform::backend_device_group group 
)

Definition at line 54 of file l500-device.cpp.

Member Function Documentation

std::vector< uint8_t > librealsense::l500_device::backup_flash ( update_progress_callback_ptr  callback)
overridevirtual

Implements librealsense::updatable.

Definition at line 482 of file l500-device.cpp.

void librealsense::l500_device::configure_depth_options ( )
virtual

Definition at line 224 of file l500-device.cpp.

std::shared_ptr< synthetic_sensor > librealsense::l500_device::create_depth_device ( std::shared_ptr< context ctx,
const std::vector< platform::uvc_device_info > &  all_device_infos 
)

Definition at line 161 of file l500-device.cpp.

void librealsense::l500_device::create_snapshot ( std::shared_ptr< debug_interface > &  snapshot) const
overridevirtual

Create a snapshot of the deriving extension. A snapshot of T is a reflection of the state and memory of T at the time of the call

Implements librealsense::recordable< debug_interface >.

Definition at line 417 of file l500-device.cpp.

void librealsense::l500_device::enable_recording ( std::function< void(const debug_interface &)>  recording_function)
overridevirtual

Instruct the derived class to begin notifying on changes Derived class should call the recording_function with a reference of themselves

Implements librealsense::recordable< debug_interface >.

Definition at line 422 of file l500-device.cpp.

void librealsense::l500_device::enter_update_state ( ) const
overridevirtual

Implements librealsense::updatable.

Definition at line 452 of file l500-device.cpp.

void librealsense::l500_device::force_hardware_reset ( ) const
protected

Definition at line 410 of file l500-device.cpp.

virtual l500_color_sensor* librealsense::l500_device::get_color_sensor ( )
pure virtual
l500_depth_sensor & librealsense::l500_device::get_depth_sensor ( )

Definition at line 155 of file l500-device.cpp.

double librealsense::l500_device::get_device_time_ms ( )
overridevirtual

Implements librealsense::global_time_interface.

Definition at line 427 of file l500-device.cpp.

command librealsense::l500_device::get_firmware_logs_command ( ) const
protected

Definition at line 637 of file l500-device.cpp.

command librealsense::l500_device::get_flash_logs_command ( ) const
protected

Definition at line 642 of file l500-device.cpp.

uvc_sensor& librealsense::l500_device::get_raw_depth_sensor ( )
inline

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

synthetic_sensor& librealsense::l500_device::get_synthetic_depth_sensor ( )
inline

Definition at line 44 of file l500-device.h.

ivcam2::extended_temperatures librealsense::l500_device::get_temperatures ( ) const

Definition at line 694 of file l500-device.cpp.

void librealsense::l500_device::hardware_reset ( )
inlineoverridevirtual

Reimplemented from librealsense::device.

Definition at line 63 of file l500-device.h.

void librealsense::l500_device::notify_of_calibration_change ( rs2_calibration_status  status)

Definition at line 371 of file l500-device.cpp.

void librealsense::l500_device::register_calibration_change_callback ( calibration_change_callback_ptr  callback)
inlineoverridevirtual

Implements librealsense::calibration_change_device.

Definition at line 52 of file l500-device.h.

std::vector< uint8_t > librealsense::l500_device::send_receive_raw_data ( const std::vector< uint8_t > &  input)
overridevirtual

Implements librealsense::debug_interface.

Definition at line 660 of file l500-device.cpp.

void librealsense::l500_device::start_temperatures_reader ( )
protected

Definition at line 728 of file l500-device.cpp.

void librealsense::l500_device::stop_temperatures_reader ( )
protected

Definition at line 781 of file l500-device.cpp.

void librealsense::l500_device::trigger_device_calibration ( rs2_calibration_type  type)
overridevirtual

Implements librealsense::device_calibration.

Definition at line 382 of file l500-device.cpp.

void librealsense::l500_device::update_flash ( const std::vector< uint8_t > &  image,
update_progress_callback_ptr  callback,
int  update_mode 
)
overridevirtual

Implements librealsense::updatable.

Definition at line 603 of file l500-device.cpp.

void librealsense::l500_device::update_flash_internal ( std::shared_ptr< hw_monitor hwm,
const std::vector< uint8_t > &  image,
std::vector< uint8_t > &  flash_backup,
update_progress_callback_ptr  callback,
int  update_mode 
)

Definition at line 583 of file l500-device.cpp.

void librealsense::l500_device::update_flash_section ( std::shared_ptr< hw_monitor hwm,
const std::vector< uint8_t > &  image,
uint32_t  offset,
uint32_t  size,
update_progress_callback_ptr  callback,
float  continue_from,
float  ratio 
)

Definition at line 532 of file l500-device.cpp.

void librealsense::l500_device::update_section ( std::shared_ptr< hw_monitor hwm,
const std::vector< uint8_t > &  merged_image,
flash_section  fs,
uint32_t  tables_size,
update_progress_callback_ptr  callback,
float  continue_from,
float  ratio 
)

Definition at line 570 of file l500-device.cpp.

Friends And Related Function Documentation

friend class l500_depth_sensor
friend

Definition at line 89 of file l500-device.h.

Member Data Documentation

std::vector<rs2_option> librealsense::l500_device::_advanced_options
protected

Definition at line 111 of file l500-device.h.

std::shared_ptr< ivcam2::ac_trigger > librealsense::l500_device::_autocal
protected

Definition at line 102 of file l500-device.h.

lazy<ivcam2::intrinsic_depth> librealsense::l500_device::_calib_table
protected

Definition at line 96 of file l500-device.h.

std::vector< calibration_change_callback_ptr > librealsense::l500_device::_calibration_change_callbacks
protected

Definition at line 113 of file l500-device.h.

std::shared_ptr<stream_interface> librealsense::l500_device::_confidence_stream
protected

Definition at line 100 of file l500-device.h.

uint8_t librealsense::l500_device::_depth_device_idx
protected

Definition at line 92 of file l500-device.h.

std::shared_ptr<stream_interface> librealsense::l500_device::_depth_stream
protected

Definition at line 98 of file l500-device.h.

firmware_version librealsense::l500_device::_fw_version
protected

Definition at line 97 of file l500-device.h.

std::atomic_bool librealsense::l500_device::_have_temperatures { false }
protected

Definition at line 118 of file l500-device.h.

std::shared_ptr<hw_monitor> librealsense::l500_device::_hw_monitor
protected

Definition at line 91 of file l500-device.h.

std::shared_ptr<stream_interface> librealsense::l500_device::_ir_stream
protected

Definition at line 99 of file l500-device.h.

bool librealsense::l500_device::_is_locked = true
protected

Definition at line 105 of file l500-device.h.

std::atomic_bool librealsense::l500_device::_keep_reading_temperature { false }
protected

Definition at line 117 of file l500-device.h.

std::shared_ptr<polling_error_handler> librealsense::l500_device::_polling_error_handler
protected

Definition at line 94 of file l500-device.h.

std::mutex librealsense::l500_device::_temperature_mutex
mutableprotected

Definition at line 116 of file l500-device.h.

std::thread librealsense::l500_device::_temperature_reader
protected

Definition at line 119 of file l500-device.h.

ivcam2::extended_temperatures librealsense::l500_device::_temperatures
protected

Definition at line 120 of file l500-device.h.

platform::usb_spec librealsense::l500_device::_usb_mode
protected

Definition at line 114 of file l500-device.h.


The documentation for this class was generated from the following files:


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