pub struct Sensor { /* private fields */ }
Expand description
Type for holding sensor-related data.
A sensor in librealsense2 corresponds to a physical component on the unit in some way, shape, or form. These may or may not correspond to multiple streams. e.g. an IMU on the device may correspond to accelerometer and gyroscope streams, or an IR camera sensor on the device may correspond to depth & video streams.
Sensors are constructed one of two ways:
- From the device’s sensor list
- By getting the sensor that corresponds to a given frame
Implementations§
Source§impl Sensor
impl Sensor
Sourcepub fn device(&self) -> Result<Device, DeviceConstructionError>
pub fn device(&self) -> Result<Device, DeviceConstructionError>
Get the parent device that this sensor corresponds to.
Returns the device that this sensor corresponds to iff that device is still connected and the sensor is still valid. Otherwise returns an error.
§Errors
Returns DeviceConstructionError::CouldNotCreateDeviceFromSensor
if the device cannot be
obtained due to the physical device being disconnected or the internal sensor pointer
becoming invalid.
Sourcepub fn extension(&self) -> Rs2Extension
pub fn extension(&self) -> Rs2Extension
Get sensor extension.
Sourcepub fn get_option(&self, option: Rs2Option) -> Option<f32>
pub fn get_option(&self, option: Rs2Option) -> Option<f32>
Get the value associated with the provided Rs2Option for the sensor.
Returns An f32
value corresponding to that option within the librealsense2 library, or None
if the option is not supported.
Sourcepub fn set_option(
&mut self,
option: Rs2Option,
value: f32,
) -> Result<(), OptionSetError>
pub fn set_option( &mut self, option: Rs2Option, value: f32, ) -> Result<(), OptionSetError>
Sets the value
associated with the provided option
for the sensor.
Returns null tuple if the option can be successfully set on the sensor, otherwise an error.
§Errors
Returns OptionSetError::OptionNotSupported
if the option is not supported on this
sensor.
Returns OptionSetError::OptionIsReadOnly
if the option is supported but cannot be set
on this sensor.
Returns OptionSetError::CouldNotSetOption
if the option is supported and not read-only,
but could not be set for another reason (invalid value, internal exception, etc.).
Sourcepub fn get_option_range(&self, option: Rs2Option) -> Option<Rs2OptionRange>
pub fn get_option_range(&self, option: Rs2Option) -> Option<Rs2OptionRange>
Gets the range for a given option.
Returns some option range if the sensor supports the option, else None
.
Sourcepub fn supports_option(&self, option: Rs2Option) -> bool
pub fn supports_option(&self, option: Rs2Option) -> bool
Predicate for determining if this sensor supports a given option
Returns true iff the option is supported by this sensor.
Sourcepub fn is_option_read_only(&self, option: Rs2Option) -> bool
pub fn is_option_read_only(&self, option: Rs2Option) -> bool
Predicate for determining if the provided option is immutable or not.
Returns true if the option is supported and can be mutated, otherwise false.
Sourcepub fn stream_profiles(&self) -> Vec<StreamProfile>
pub fn stream_profiles(&self) -> Vec<StreamProfile>
Get a list of stream profiles associated with this sensor
Returns a vector containing all the stream profiles associated with the sensor. The vector will have a length of zero if an error occurs while getting the stream profiles.
Sourcepub fn info(&self, camera_info: Rs2CameraInfo) -> Option<&CStr>
pub fn info(&self, camera_info: Rs2CameraInfo) -> Option<&CStr>
Gets the value associated with the provided camera info key from the sensor.
Returns some value corresponding to the camera info requested if this sensor supports that
camera info, else None
.
Sourcepub fn supports_info(&self, camera_info: Rs2CameraInfo) -> bool
pub fn supports_info(&self, camera_info: Rs2CameraInfo) -> bool
Predicate method for determining if the sensor supports a certain kind of camera info.
Returns true iff the sensor has a value associated with the camera_info
key.
Sourcepub fn get_region_of_interest(&self) -> Option<Rs2Roi>
pub fn get_region_of_interest(&self) -> Option<Rs2Roi>
Gets the auto exposure’s region of interest for the sensor.
Returns the region of interest for the auto exposure or None if this isn’t available.
Sourcepub fn set_region_of_interest(&mut self, roi: Rs2Roi) -> Result<(), RoiSetError>
pub fn set_region_of_interest(&mut self, roi: Rs2Roi) -> Result<(), RoiSetError>
Sets the auto exposure’s region of interest to roi
for the sensor.
Returns null tuple if the region of interest was set successfully, otherwise an error.
§Errors
Returns RoiSetError::CouldNotSetRoi
if setting the region of interest failed.
§Known issues
This command can fail directly after the pipeline start. This is a bug in librealsense. Either wait for the first Frameset to be received or repeat the command in a loop with a delay until it succeeds as suggested by Intel. Issue at librealsense: https://github.com/IntelRealSense/librealsense/issues/8004
Trait Implementations§
Source§impl From<NonNull<rs2_sensor>> for Sensor
impl From<NonNull<rs2_sensor>> for Sensor
Source§fn from(sensor_ptr: NonNull<rs2_sensor>) -> Self
fn from(sensor_ptr: NonNull<rs2_sensor>) -> Self
Attempt to construct a Sensor from a non-null pointer to rs2_sensor
.