realsense_rust/kind/
camera_info.rs

1//! Enumeration of sensor and device information keys.
2
3use num_derive::{FromPrimitive, ToPrimitive};
4use realsense_sys as sys;
5
6/// A type describing the different keys used to access camera info from devices and sensors.
7///
8/// Each key corresponds to a particular type of device or sensor-specific metadata (known as
9/// `info` in the librealsense2 API). Not all keys are supported on all devices or sensors.
10///
11/// All values that correspond to these keys are returned in the lower level API as `const char*`
12/// types, or C-strings. We wrap these values in the `realsense-rust` API as `&CStr` types.
13///
14#[repr(i32)]
15#[derive(FromPrimitive, ToPrimitive, Debug, Clone, Copy, PartialEq, Eq, Hash)]
16pub enum Rs2CameraInfo {
17    /// The name of the sensor or device.
18    Name = sys::rs2_camera_info_RS2_CAMERA_INFO_NAME as i32,
19    /// The serial number of the device.
20    SerialNumber = sys::rs2_camera_info_RS2_CAMERA_INFO_SERIAL_NUMBER as i32,
21    /// The firmware version that the device is running.
22    FirmwareVersion = sys::rs2_camera_info_RS2_CAMERA_INFO_FIRMWARE_VERSION as i32,
23    /// The recommended firmware version for a given device.
24    ///
25    /// The value that corresponds to this key may change depending on what version of
26    /// librealsense2 this crate is built against!
27    RecommendedFirmwareVersion =
28        sys::rs2_camera_info_RS2_CAMERA_INFO_RECOMMENDED_FIRMWARE_VERSION as i32,
29    /// A description of the unique identifier of the physical port that the device is connected to.
30    ///
31    /// The format of the value associated with this key will be platform specific.
32    PhysicalPort = sys::rs2_camera_info_RS2_CAMERA_INFO_PHYSICAL_PORT as i32,
33    /// If the device supports firmware logging, this is the command you send to get those logs.
34    DebugOpCode = sys::rs2_camera_info_RS2_CAMERA_INFO_DEBUG_OP_CODE as i32,
35    /// Tells you whether the device is in advanced mode.
36    AdvancedMode = sys::rs2_camera_info_RS2_CAMERA_INFO_ADVANCED_MODE as i32,
37    /// The product identifier for the device (as reported by its USB descriptor).
38    ProductId = sys::rs2_camera_info_RS2_CAMERA_INFO_PRODUCT_ID as i32,
39    /// Tells you whether the EEPROM is locked.
40    CameraLocked = sys::rs2_camera_info_RS2_CAMERA_INFO_CAMERA_LOCKED as i32,
41    /// Tells you the designated USB specification (i.e. USB2 or USB3).
42    UsbTypeDescriptor = sys::rs2_camera_info_RS2_CAMERA_INFO_USB_TYPE_DESCRIPTOR as i32,
43    /// Device product line (e.g. D400 / SR300 / L500 / T200)
44    ProductLine = sys::rs2_camera_info_RS2_CAMERA_INFO_PRODUCT_LINE as i32,
45    /// The ASIC serial number of the device.
46    AsicSerialNumber = sys::rs2_camera_info_RS2_CAMERA_INFO_ASIC_SERIAL_NUMBER as i32,
47    /// Provides the firmware update identifier for the device.
48    FirmwareUpdateId = sys::rs2_camera_info_RS2_CAMERA_INFO_FIRMWARE_UPDATE_ID as i32,
49    /// IP address for remote camera.
50    IpAddress = sys::rs2_camera_info_RS2_CAMERA_INFO_IP_ADDRESS as i32,
51    // Not included since this just tells us the total number of camera info options
52    //
53    // Count = sys::rs2_camera_info_RS2_CAMERA_INFO_COUNT,
54}
55
56#[cfg(test)]
57mod tests {
58    use super::*;
59    use num_traits::FromPrimitive;
60
61    #[test]
62    fn all_variants_exist() {
63        for i in 0..sys::rs2_camera_info_RS2_CAMERA_INFO_COUNT as i32 {
64            assert!(
65                Rs2CameraInfo::from_i32(i).is_some(),
66                "Rs2CameraInfo variant for ordinal {} does not exist.",
67                i,
68            );
69        }
70    }
71}