Struct Sensor

Source
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:

  1. From the device’s sensor list
  2. By getting the sensor that corresponds to a given frame

Implementations§

Source§

impl Sensor

Source

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.

Source

pub fn extension(&self) -> Rs2Extension

Get sensor extension.

Source

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.

Source

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.).

Source

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.

Source

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.

Source

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.

Source

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.

Source

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.

Source

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.

Source

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.

Source

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 Drop for Sensor

Source§

fn drop(&mut self)

Executes the destructor for this type. Read more
Source§

impl From<NonNull<rs2_sensor>> for Sensor

Source§

fn from(sensor_ptr: NonNull<rs2_sensor>) -> Self

Attempt to construct a Sensor from a non-null pointer to rs2_sensor.

Source§

impl Send for Sensor

Auto Trait Implementations§

Blanket Implementations§

Source§

impl<T> Any for T
where T: 'static + ?Sized,

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

impl<T> Borrow<T> for T
where T: ?Sized,

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

Source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T, U> Into<U> for T
where U: From<T>,

Source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Source§

type Error = Infallible

The type returned in the event of a conversion error.
Source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Source§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
Source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.