Structure containing information about a single sensor available in the current deviceThat information about the camera sensors is available in the CameraInformation struct returned by Camera.get_camera_information() More...
Functions | |
def | sensor_type (self) |
The type of the sensor as SENSOR_TYPE. | |
def | resolution (self) |
The resolution of the sensor. | |
def | sampling_rate (self) |
The sampling rate (or ODR) of the sensor. | |
def | sensor_range (self) |
The range values of the sensor. More... | |
def | set_sensor_range (self, float value1, float value2) |
Sets the minimum and the maximum values of the sensor range. More... | |
def | noise_density (self) |
Also known as white noise, given as continous (frequency independent). More... | |
def | random_walk (self) |
derived from the Allan Variance, given as continous (frequency independent). More... | |
def | sensor_unit (self) |
The string relative to the measurement unit of the sensor. | |
def | is_available (self) |
Defines if the sensor is available in your camera. | |
Structure containing information about a single sensor available in the current device
That information about the camera sensors is available in the CameraInformation struct returned by Camera.get_camera_information()
def sensor_range | ( | self | ) |
The range values of the sensor.
MIN: sensor_range[0]
, MAX: sensor_range[1]
def set_sensor_range | ( | self, | |
float | value1, | ||
float | value2 | ||
) |
Sets the minimum and the maximum values of the sensor range.
float | value1 : min range value of the sensor |
float | value2 : max range value of the sensor |
def noise_density | ( | self | ) |
Also known as white noise, given as continous (frequency independent).
Units will be expressed in sensor_unit/√(Hz). NAN
if the information is not available
def random_walk | ( | self | ) |
derived from the Allan Variance, given as continous (frequency independent).
Units will be expressed in sensor_unit/s/√(Hz).NAN
if the information is not available