1
  2
  3
  4
  5
  6
  7
  8
  9
 10
 11
 12
 13
 14
 15
 16
 17
 18
 19
 20
 21
 22
 23
 24
 25
 26
 27
 28
 29
 30
 31
 32
 33
 34
 35
 36
 37
 38
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
//! Defines the device types.

use crate::{
    common::*,
    error::{ErrorChecker, Result},
    kind::CameraInfo,
    sensor_list::SensorList,
};

/// Represents a device instance.
#[derive(Debug)]
pub struct Device {
    pub(crate) ptr: NonNull<sys::rs2_device>,
}

impl Device {
    /// Discover available sensors on device.
    pub fn query_sensors(&self) -> Result<SensorList> {
        let list = unsafe {
            let mut checker = ErrorChecker::new();
            let ptr = sys::rs2_query_sensors(self.ptr.as_ptr(), checker.inner_mut_ptr());
            checker.check()?;
            SensorList::from_raw(ptr)
        };
        Ok(list)
    }

    pub fn hardware_reset(&self) -> Result<()> {
        unsafe {
            let mut checker = ErrorChecker::new();
            sys::rs2_hardware_reset(self.ptr.as_ptr(), checker.inner_mut_ptr());
            checker.check()?;
        }
        Ok(())
    }

    pub fn name(&self) -> Result<Option<&str>> {
        self.info(CameraInfo::Name)
    }

    pub fn serial_number(&self) -> Result<Option<&str>> {
        self.info(CameraInfo::SerialNumber)
    }

    pub fn recommended_firmware_version(&self) -> Result<Option<&str>> {
        self.info(CameraInfo::RecommendedFirmwareVersion)
    }

    pub fn physical_port(&self) -> Result<Option<&str>> {
        self.info(CameraInfo::PhysicalPort)
    }

    pub fn debug_op_code(&self) -> Result<Option<&str>> {
        self.info(CameraInfo::DebugOpCode)
    }

    pub fn advanced_mode(&self) -> Result<Option<&str>> {
        self.info(CameraInfo::AdvancedMode)
    }

    pub fn product_id(&self) -> Result<Option<&str>> {
        self.info(CameraInfo::ProductId)
    }

    pub fn camera_locked(&self) -> Result<Option<&str>> {
        self.info(CameraInfo::CameraLocked)
    }

    pub fn usb_type_descriptor(&self) -> Result<Option<&str>> {
        self.info(CameraInfo::UsbTypeDescriptor)
    }

    pub fn product_line(&self) -> Result<Option<&str>> {
        self.info(CameraInfo::ProductLine)
    }

    pub fn asic_serial_number(&self) -> Result<Option<&str>> {
        self.info(CameraInfo::AsicSerialNumber)
    }

    pub fn firmware_update_id(&self) -> Result<Option<&str>> {
        self.info(CameraInfo::FirmwareUpdateId)
    }

    pub fn count(&self) -> Result<Option<&str>> {
        self.info(CameraInfo::Count)
    }

    pub fn info(&self, kind: CameraInfo) -> Result<Option<&str>> {
        if !self.is_info_supported(kind)? {
            return Ok(None);
        }

        let ptr = unsafe {
            let mut checker = ErrorChecker::new();
            let ptr = sys::rs2_get_device_info(
                self.ptr.as_ptr(),
                kind as sys::rs2_camera_info,
                checker.inner_mut_ptr(),
            );
            checker.check()?;
            ptr
        };

        // TODO: deallicate this CStr?
        let string = unsafe { CStr::from_ptr(ptr).to_str().unwrap() };
        Ok(Some(string))
    }

    pub fn is_info_supported(&self, kind: CameraInfo) -> Result<bool> {
        let val = unsafe {
            let mut checker = ErrorChecker::new();
            let val = sys::rs2_supports_device_info(
                self.ptr.as_ptr(),
                kind as sys::rs2_camera_info,
                checker.inner_mut_ptr(),
            );
            checker.check()?;
            val
        };
        Ok(val != 0)
    }

    pub fn into_raw(self) -> *mut sys::rs2_device {
        let ptr = self.ptr;
        mem::forget(self);
        ptr.as_ptr()
    }

    pub unsafe fn from_raw(ptr: *mut sys::rs2_device) -> Self {
        Self {
            ptr: NonNull::new(ptr).unwrap(),
        }
    }
}

impl Drop for Device {
    fn drop(&mut self) {
        unsafe {
            sys::rs2_delete_device(self.ptr.as_ptr());
        }
    }
}

unsafe impl Send for Device {}