#include <sr300.h>
Classes | |
class | preset_option |
class | sr300_depth_sensor |
Public Member Functions | |
std::vector< uint8_t > | backup_flash (update_progress_callback_ptr callback) override |
std::shared_ptr< synthetic_sensor > | create_depth_device (std::shared_ptr< context > ctx, const platform::uvc_device_info &depth) |
virtual std::shared_ptr< matcher > | create_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_sensor & | get_depth_sensor () |
std::vector< tagged_profile > | get_profiles_tags () const override |
uvc_sensor & | get_raw_depth_sensor () |
void | hardware_reset () override |
void | rs2_apply_ivcam_preset (int preset) |
std::vector< uint8_t > | send_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< context > | get_context () const override |
platform::backend_device_group | get_device_data () const override |
std::pair< uint32_t, rs2_extrinsics > | get_extrinsics (const stream_interface &stream) const override |
sensor_interface & | get_sensor (size_t subdevice) override |
const sensor_interface & | get_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::string & | get_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_format > | map_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 |
Definition at line 193 of file src/ivcam/sr300.h.
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 | ||
) |
|
overridevirtual |
Implements librealsense::updatable.
std::shared_ptr< synthetic_sensor > librealsense::sr3xx_camera::create_depth_device | ( | std::shared_ptr< context > | ctx, |
const platform::uvc_device_info & | depth | ||
) |
|
overridevirtual |
Reimplemented from librealsense::device.
Reimplemented in librealsense::sr300_camera.
|
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 >.
|
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 >.
|
private |
|
overridevirtual |
Implements librealsense::updatable.
|
private |
|
private |
|
inline |
Definition at line 336 of file src/ivcam/sr300.h.
|
protected |
|
protected |
|
inlineoverridevirtual |
Implements librealsense::device_interface.
Reimplemented in librealsense::sr306_camera, and librealsense::sr300_camera.
Definition at line 199 of file src/ivcam/sr300.h.
|
inline |
Definition at line 338 of file src/ivcam/sr300.h.
|
inlineoverridevirtual |
Reimplemented from librealsense::device.
Definition at line 331 of file src/ivcam/sr300.h.
|
staticprivate |
|
private |
|
private |
|
inlineprivate |
Definition at line 442 of file src/ivcam/sr300.h.
|
inlineprivate |
Definition at line 430 of file src/ivcam/sr300.h.
|
inline |
Definition at line 350 of file src/ivcam/sr300.h.
|
inlineoverridevirtual |
Implements librealsense::debug_interface.
Definition at line 326 of file src/ivcam/sr300.h.
|
private |
|
overridevirtual |
Implements librealsense::updatable.
|
protected |
Definition at line 478 of file src/ivcam/sr300.h.
|
private |
Definition at line 426 of file src/ivcam/sr300.h.
|
protected |
Definition at line 474 of file src/ivcam/sr300.h.
|
protected |
Definition at line 477 of file src/ivcam/sr300.h.
|
protected |
Definition at line 476 of file src/ivcam/sr300.h.
|
protected |
Definition at line 475 of file src/ivcam/sr300.h.
|
private |
Definition at line 427 of file src/ivcam/sr300.h.