Public Member Functions | List of all members
librealsense::rs465_device Class Reference
Inheritance diagram for librealsense::rs465_device:
Inheritance graph
[legend]

Public Member Functions

std::shared_ptr< matchercreate_matcher (const frame_holder &frame) const override
 
std::vector< tagged_profileget_profiles_tags () const override
 
 rs465_device (std::shared_ptr< context > ctx, const platform::backend_device_group &group, bool register_device_notifications)
 
- Public Member Functions inherited from librealsense::ds5_active
 ds5_active (std::shared_ptr< context > ctx, const platform::backend_device_group &group)
 
- Public Member Functions inherited from librealsense::ds5_device
std::vector< uint8_tbackup_flash (update_progress_callback_ptr callback) override
 
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
 
 ds5_device (std::shared_ptr< context > ctx, const platform::backend_device_group &group)
 
void enable_recording (std::function< void(const debug_interface &)> record_action) override
 
void enter_update_state () const override
 
synthetic_sensorget_depth_sensor ()
 
virtual double get_device_time_ms () override
 
uvc_sensorget_raw_depth_sensor ()
 
platform::usb_spec get_usb_spec () const
 
void hardware_reset () override
 
std::vector< uint8_tsend_receive_raw_data (const std::vector< uint8_t > &input) override
 
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::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
 
- Public Member Functions inherited from librealsense::auto_calibrated
 auto_calibrated (std::shared_ptr< hw_monitor > &hwm)
 
std::vector< uint8_tget_calibration_table () const override
 
void reset_to_factory_calibration () const override
 
std::vector< uint8_trun_on_chip_calibration (int timeout_ms, std::string json, float *health, update_progress_callback_ptr progress_callback) override
 
std::vector< uint8_trun_tare_calibration (int timeout_ms, float ground_truth_mm, std::string json, update_progress_callback_ptr progress_callback) override
 
void set_calibration_table (const std::vector< uint8_t > &calibration) override
 
void write_calibration () const override
 
- Public Member Functions inherited from librealsense::ds5_nonmonochrome
 ds5_nonmonochrome (std::shared_ptr< context > ctx, const platform::backend_device_group &group)
 
- Public Member Functions inherited from librealsense::ds5_color
 ds5_color (std::shared_ptr< context > ctx, const platform::backend_device_group &group)
 
synthetic_sensorget_color_sensor ()
 
uvc_sensorget_raw_color_sensor ()
 
- Public Member Functions inherited from librealsense::ds5_motion
std::shared_ptr< synthetic_sensorcreate_hid_device (std::shared_ptr< context > ctx, const std::vector< platform::hid_device_info > &all_hid_infos, const firmware_version &camera_fw_version)
 
 ds5_motion (std::shared_ptr< context > ctx, const platform::backend_device_group &group)
 
rs2_motion_device_intrinsic get_motion_intrinsics (rs2_stream) const
 
std::shared_ptr< auto_exposure_mechanismregister_auto_exposure_options (synthetic_sensor *ep, const platform::extension_unit *fisheye_xu)
 
- Public Member Functions inherited from librealsense::ds5_advanced_mode_base
void apply_preset (const std::vector< platform::stream_profile > &configuration, rs2_rs400_visual_preset preset, uint16_t device_pid, const firmware_version &fw_version) override
 
void create_snapshot (std::shared_ptr< ds5_advanced_mode_interface > &snapshot) const override
 
 ds5_advanced_mode_base (std::shared_ptr< hw_monitor > hwm, synthetic_sensor &depth_sensor)
 
void enable_recording (std::function< void(const ds5_advanced_mode_interface &)> recording_function) override
 
void get_ae_control (STAEControl *ptr, int mode=0) const override
 
void get_amp_factor (STAFactor *ptr, int mode=0) const override
 
void get_census_radius (STCensusRadius *ptr, int mode=0) const override
 
void get_color_control (STColorControl *ptr, int mode=0) const override
 
void get_color_correction (STColorCorrection *ptr, int mode=0) const override
 
void get_depth_control_group (STDepthControlGroup *ptr, int mode=0) const override
 
void get_depth_table_control (STDepthTableControl *ptr, int mode=0) const override
 
void get_hdad (STHdad *ptr, int mode=0) const override
 
void get_rau_color_thresholds_control (STRauColorThresholdsControl *ptr, int mode=0) const override
 
void get_rau_support_vector_control (STRauSupportVectorControl *ptr, int mode=0) const override
 
void get_rsm (STRsm *ptr, int mode=0) const override
 
void get_slo_color_thresholds_control (STSloColorThresholdsControl *ptr, int mode=0) const override
 
void get_slo_penalty_control (STSloPenaltyControl *ptr, int mode=0) const override
 
bool is_enabled () const override
 
void load_json (const std::string &json_content) override
 
std::vector< uint8_tserialize_json () const override
 
void set_ae_control (const STAEControl &val) override
 
void set_amp_factor (const STAFactor &val) override
 
void set_census_radius (const STCensusRadius &val) override
 
void set_color_control (const STColorControl &val) override
 
void set_color_correction (const STColorCorrection &val) override
 
void set_depth_control_group (const STDepthControlGroup &val) override
 
void set_depth_table_control (const STDepthTableControl &val) override
 
void set_hdad (const STHdad &val) override
 
void set_rau_color_thresholds_control (const STRauColorThresholdsControl &val) override
 
void set_rau_support_vector_control (const STRauSupportVectorControl &val) override
 
void set_rsm (const STRsm &val) override
 
void set_slo_color_thresholds_control (const STSloColorThresholdsControl &val) override
 
void set_slo_penalty_control (const STSloPenaltyControl &val) override
 
void toggle_advanced_mode (bool enable) override
 
virtual ~ds5_advanced_mode_base ()=default
 
- Public Member Functions inherited from librealsense::ds5_advanced_mode_interface
virtual ~ds5_advanced_mode_interface ()=default
 
- Public Member Functions inherited from librealsense::recordable< ds5_advanced_mode_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
 

Additional Inherited Members

- Static Public Attributes inherited from librealsense::ds5_advanced_mode_base
static const uint16_t HW_MONITOR_BUFFER_SIZE = 1024
 
static const uint16_t HW_MONITOR_COMMAND_SIZE = 1000
 
- Protected Member Functions inherited from librealsense::ds5_device
command get_firmware_logs_command () const
 
command get_flash_logs_command () const
 
std::vector< uint8_tget_new_calibration_table () const
 
std::vector< uint8_tget_raw_calibration_table (ds::calibration_table_id table_id) const
 
float get_stereo_baseline_mm () const
 
void init (std::shared_ptr< context > ctx, const platform::backend_device_group &group)
 
bool is_camera_in_advanced_mode () const
 
ds::d400_caps parse_device_capabilities () 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 inherited from librealsense::ds5_device
lazy< std::vector< uint8_t > > _coefficients_table_raw
 
lazy< std::vector< uint8_t > > _color_calib_table_raw
 
std::shared_ptr< lazy< rs2_extrinsics > > _color_extrinsic
 
std::shared_ptr< stream_interface_color_stream
 
uint8_t _depth_device_idx
 
std::shared_ptr< stream_interface_depth_stream
 
ds::d400_caps _device_capabilities
 
firmware_version _fw_version
 
std::shared_ptr< hw_monitor_hw_monitor
 
bool _is_locked = true
 
std::shared_ptr< stream_interface_left_ir_stream
 
std::shared_ptr< lazy< rs2_extrinsics > > _left_right_extrinsics
 
lazy< std::vector< uint8_t > > _new_calib_table_raw
 
uint16_t _pid
 
std::shared_ptr< polling_error_handler_polling_error_handler
 
firmware_version _recommended_fw_version
 
std::shared_ptr< stream_interface_right_ir_stream
 
std::shared_ptr< ds5_thermal_monitor_thermal_monitor
 
- 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
 
- Protected Attributes inherited from librealsense::ds5_color
std::shared_ptr< stream_interface_color_stream
 
- Protected Attributes inherited from librealsense::ds5_motion
std::shared_ptr< stream_interface_accel_stream
 
std::shared_ptr< stream_interface_fisheye_stream
 
std::shared_ptr< stream_interface_gyro_stream
 

Detailed Description

Definition at line 833 of file ds5-factory.cpp.

Constructor & Destructor Documentation

librealsense::rs465_device::rs465_device ( std::shared_ptr< context ctx,
const platform::backend_device_group group,
bool  register_device_notifications 
)
inline

Definition at line 841 of file ds5-factory.cpp.

Member Function Documentation

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

Reimplemented from librealsense::device.

Definition at line 1166 of file ds5-factory.cpp.

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

Implements librealsense::device_interface.

Definition at line 857 of file ds5-factory.cpp.


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


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