Classes | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
librealsense::sr3xx_camera Class Reference

#include <sr300.h>

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

Classes

class  preset_option
 
class  sr300_depth_sensor
 

Public Member Functions

std::vector< uint8_tbackup_flash (update_progress_callback_ptr callback) override
 
std::shared_ptr< synthetic_sensorcreate_depth_device (std::shared_ptr< context > ctx, const platform::uvc_device_info &depth)
 
virtual std::shared_ptr< matchercreate_matcher (const frame_holder &frame) const override
 
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
 
synthetic_sensorget_depth_sensor ()
 
std::vector< tagged_profileget_profiles_tags () const override
 
uvc_sensorget_raw_depth_sensor ()
 
void hardware_reset () override
 
void rs2_apply_ivcam_preset (int preset)
 
std::vector< uint8_tsend_receive_raw_data (const std::vector< uint8_t > &input) override
 
 sr3xx_camera (std::shared_ptr< context > ctx, const platform::uvc_device_info &depth, const platform::usb_device_info &hwm_device, const platform::backend_device_group &group, bool register_device_notifications)
 
void update_flash (const std::vector< uint8_t > &image, update_progress_callback_ptr callback, int update_mode) override
 
- 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
 
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 ~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::firmware_logger_device
void assign_hw_monitor (std::shared_ptr< hw_monitor > hardware_monitor)
 
 firmware_logger_device (std::shared_ptr< context > ctx, const platform::backend_device_group group, std::shared_ptr< hw_monitor > hardware_monitor, const command &fw_logs_command, const command &flash_logs_command)
 
bool get_flash_log (fw_logs::fw_logs_binary_data &binary_data) override
 
bool get_fw_log (fw_logs::fw_logs_binary_data &binary_data) override
 
unsigned int get_number_of_fw_logs () const override
 
bool init_parser (std::string xml_content) override
 
bool parse_log (const fw_logs::fw_logs_binary_data *fw_log_msg, fw_logs::fw_log_data *parsed_msg) override
 
- Public Member Functions inherited from librealsense::firmware_logger_extensions
virtual ~firmware_logger_extensions ()=default
 

Protected Member Functions

command get_firmware_logs_command () const
 
command get_flash_logs_command () const
 
- 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

lazy< ivcam::camera_calib_params_camer_calib_params
 
std::shared_ptr< stream_interface_depth_stream
 
std::shared_ptr< lazy< rs2_extrinsics > > _depth_to_color_extrinsics
 
std::shared_ptr< hw_monitor_hw_monitor
 
std::shared_ptr< stream_interface_ir_stream
 
- Protected Attributes inherited from librealsense::device
std::map< int, std::pair< uint32_t, std::shared_ptr< const stream_interface > > > _extrinsics
 

Private Member Functions

void enable_timestamp (bool colorEnable, bool depthEnable) const
 
void force_hardware_reset () const
 
ivcam::camera_calib_params get_calibration () const
 
int read_ir_temp () const
 
float read_mems_temp () const
 
void register_autorange_options ()
 
template<class T >
void register_depth_xu (synthetic_sensor &depth, rs2_option opt, uint8_t id, std::string desc) const
 
void set_auto_range (const ivcam::cam_auto_range_request &c) const
 

Static Private Member Functions

static rs2_intrinsics make_depth_intrinsics (const ivcam::camera_calib_params &c, const int2 &dims)
 

Private Attributes

const uint8_t _depth_device_idx
 
bool _is_locked = true
 

Detailed Description

Definition at line 193 of file src/ivcam/sr300.h.

Constructor & Destructor Documentation

librealsense::sr3xx_camera::sr3xx_camera ( std::shared_ptr< context ctx,
const platform::uvc_device_info depth,
const platform::usb_device_info hwm_device,
const platform::backend_device_group group,
bool  register_device_notifications 
)

Definition at line 445 of file sr300.cpp.

Member Function Documentation

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

Implements librealsense::updatable.

Definition at line 363 of file sr300.cpp.

std::shared_ptr< synthetic_sensor > librealsense::sr3xx_camera::create_depth_device ( std::shared_ptr< context ctx,
const platform::uvc_device_info depth 
)

Definition at line 177 of file sr300.cpp.

std::shared_ptr< matcher > librealsense::sr3xx_camera::create_matcher ( const frame_holder frame) const
overridevirtual

Reimplemented from librealsense::device.

Reimplemented in librealsense::sr300_camera.

Definition at line 650 of file sr300.cpp.

void librealsense::sr3xx_camera::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 572 of file sr300.cpp.

void librealsense::sr3xx_camera::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 576 of file sr300.cpp.

void librealsense::sr3xx_camera::enable_timestamp ( bool  colorEnable,
bool  depthEnable 
) const
private

Definition at line 296 of file sr300.cpp.

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

Implements librealsense::updatable.

Definition at line 335 of file sr300.cpp.

void librealsense::sr3xx_camera::force_hardware_reset ( ) const
private

Definition at line 289 of file sr300.cpp.

ivcam::camera_calib_params librealsense::sr3xx_camera::get_calibration ( ) const
private

Definition at line 434 of file sr300.cpp.

synthetic_sensor& librealsense::sr3xx_camera::get_depth_sensor ( )
inline

Definition at line 336 of file src/ivcam/sr300.h.

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

Definition at line 562 of file sr300.cpp.

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

Definition at line 567 of file sr300.cpp.

std::vector<tagged_profile> librealsense::sr3xx_camera::get_profiles_tags ( ) const
inlineoverridevirtual

Implements librealsense::device_interface.

Reimplemented in librealsense::sr306_camera, and librealsense::sr300_camera.

Definition at line 199 of file src/ivcam/sr300.h.

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

Definition at line 338 of file src/ivcam/sr300.h.

void librealsense::sr3xx_camera::hardware_reset ( )
inlineoverridevirtual

Reimplemented from librealsense::device.

Definition at line 331 of file src/ivcam/sr300.h.

rs2_intrinsics librealsense::sr3xx_camera::make_depth_intrinsics ( const ivcam::camera_calib_params c,
const int2 dims 
)
staticprivate

Definition at line 242 of file sr300.cpp.

int librealsense::sr3xx_camera::read_ir_temp ( ) const
private

Definition at line 282 of file sr300.cpp.

float librealsense::sr3xx_camera::read_mems_temp ( ) const
private

Definition at line 274 of file sr300.cpp.

void librealsense::sr3xx_camera::register_autorange_options ( )
inlineprivate

Definition at line 442 of file src/ivcam/sr300.h.

template<class T >
void librealsense::sr3xx_camera::register_depth_xu ( synthetic_sensor depth,
rs2_option  opt,
uint8_t  id,
std::string  desc 
) const
inlineprivate

Definition at line 430 of file src/ivcam/sr300.h.

void librealsense::sr3xx_camera::rs2_apply_ivcam_preset ( int  preset)
inline

Definition at line 350 of file src/ivcam/sr300.h.

std::vector<uint8_t> librealsense::sr3xx_camera::send_receive_raw_data ( const std::vector< uint8_t > &  input)
inlineoverridevirtual

Implements librealsense::debug_interface.

Definition at line 326 of file src/ivcam/sr300.h.

void librealsense::sr3xx_camera::set_auto_range ( const ivcam::cam_auto_range_request c) const
private

Definition at line 304 of file sr300.cpp.

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

Implements librealsense::updatable.

Definition at line 410 of file sr300.cpp.

Member Data Documentation

lazy<ivcam::camera_calib_params> librealsense::sr3xx_camera::_camer_calib_params
protected

Definition at line 478 of file src/ivcam/sr300.h.

const uint8_t librealsense::sr3xx_camera::_depth_device_idx
private

Definition at line 426 of file src/ivcam/sr300.h.

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

Definition at line 474 of file src/ivcam/sr300.h.

std::shared_ptr<lazy<rs2_extrinsics> > librealsense::sr3xx_camera::_depth_to_color_extrinsics
protected

Definition at line 477 of file src/ivcam/sr300.h.

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

Definition at line 476 of file src/ivcam/sr300.h.

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

Definition at line 475 of file src/ivcam/sr300.h.

bool librealsense::sr3xx_camera::_is_locked = true
private

Definition at line 427 of file src/ivcam/sr300.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:38