realsense_rust/device.rs
1//! A type for abstracting over the concept of a RealSense "device"
2//!
3//! A device in librealsense2 refers to a complete set of sensors that comprise e.g. a D400 / L500
4//! / T200 unit. A D435 or D435i, for example, is a device, whereas the individual parts that
5//! comprise that device (IR cameras, depth camera, color camera, IMU) are referred to as sensors.
6//! See [`sensors`](crate::sensor) for more info.
7
8use crate::{
9 check_rs2_error,
10 kind::{Rs2CameraInfo, Rs2Exception},
11 sensor::Sensor,
12};
13use anyhow::Result;
14use realsense_sys as sys;
15use std::{
16 convert::{From, TryInto},
17 ffi::CStr,
18 ptr::NonNull,
19};
20use thiserror::Error;
21
22/// Enumeration of possible errors that can occur during device construction
23#[derive(Error, Debug)]
24pub enum DeviceConstructionError {
25 /// System was unable to get the device pointer that corresponds to a given [`Sensor`]
26 #[error("Could not create device from sensor. Type: {0}; Reason: {1}")]
27 CouldNotCreateDeviceFromSensor(Rs2Exception, String),
28 /// Could not get device from device list
29 #[error("Could not get device from device list. Type: {0}; Reason: {1}")]
30 CouldNotGetDeviceFromDeviceList(Rs2Exception, String),
31}
32
33/// A type representing a RealSense device.
34///
35/// A device in librealsense2 corresponds to a physical unit that connects to your computer
36/// (usually via USB). Devices hold a list of sensors, which in turn are represented by a list of
37/// streams producing frames.
38///
39/// Devices are usually acquired by the driver context.
40///
41#[derive(Debug)]
42pub struct Device {
43 /// A non-null pointer to the underlying librealsense device
44 device_ptr: NonNull<sys::rs2_device>,
45}
46
47impl Drop for Device {
48 fn drop(&mut self) {
49 unsafe {
50 sys::rs2_delete_device(self.device_ptr.as_ptr());
51 }
52 }
53}
54
55unsafe impl Send for Device {}
56
57impl From<NonNull<sys::rs2_device>> for Device {
58 /// Attempt to construct a Device from a non-null pointer to `rs2_device`.
59 ///
60 /// Constructs a device from a pointer to an `rs2_device` type from the C-FFI.
61 ///
62 fn from(device_ptr: NonNull<sys::rs2_device>) -> Self {
63 Device { device_ptr }
64 }
65}
66
67impl Device {
68 /// Attempt to construct a Device given a device list and index into the device list.
69 ///
70 /// # Errors
71 ///
72 /// Returns [`DeviceConstructionError::CouldNotGetDeviceFromDeviceList`] if the device cannot
73 /// be retrieved from the device list (e.g. if the index is invalid).
74 ///
75 pub(crate) fn try_create(
76 device_list: &NonNull<sys::rs2_device_list>,
77 index: i32,
78 ) -> Result<Self, DeviceConstructionError> {
79 unsafe {
80 let mut err = std::ptr::null_mut::<sys::rs2_error>();
81
82 let device_ptr = sys::rs2_create_device(device_list.as_ptr(), index, &mut err);
83 check_rs2_error!(
84 err,
85 DeviceConstructionError::CouldNotGetDeviceFromDeviceList
86 )?;
87
88 let nonnull_device_ptr = NonNull::new(device_ptr).unwrap();
89 Ok(Device::from(nonnull_device_ptr))
90 }
91 }
92
93 /// Gets a list of sensors associated with the device.
94 ///
95 /// Returns a vector of zero size if any error occurs while trying to read the sensor list.
96 /// This can occur if the physical device is disconnected before this call is made.
97 ///
98 pub fn sensors(&self) -> Vec<Sensor> {
99 unsafe {
100 let mut sensors = Vec::new();
101
102 let mut err = std::ptr::null_mut::<sys::rs2_error>();
103 let sensor_list_ptr = sys::rs2_query_sensors(self.device_ptr.as_ptr(), &mut err);
104
105 if err.as_ref().is_some() {
106 sys::rs2_free_error(err);
107 return sensors;
108 }
109
110 let nonnull_sensor_list = NonNull::new(sensor_list_ptr).unwrap();
111
112 let len = sys::rs2_get_sensors_count(nonnull_sensor_list.as_ptr(), &mut err);
113
114 if err.as_ref().is_some() {
115 sys::rs2_free_error(err);
116 sys::rs2_delete_sensor_list(nonnull_sensor_list.as_ptr());
117 return sensors;
118 }
119
120 sensors.reserve(len as usize);
121 for i in 0..len {
122 match Sensor::try_create(&nonnull_sensor_list, i) {
123 Ok(s) => {
124 sensors.push(s);
125 }
126 Err(_) => {
127 continue;
128 }
129 }
130 }
131 sys::rs2_delete_sensor_list(nonnull_sensor_list.as_ptr());
132 sensors
133 }
134 }
135
136 /// Takes ownership of the device and forces a hardware reset on the device.
137 ///
138 /// Ownership of the device is taken as the underlying state can no longer be safely retained
139 /// after resetting the device.
140 ///
141 pub fn hardware_reset(self) {
142 unsafe {
143 let mut err = std::ptr::null_mut::<sys::rs2_error>();
144
145 // The only failure this can have is if device_ptr is null. This should not be the case
146 // since we're storing a `NonNull` type.
147 //
148 // It's a bit weird, but we don't need to actually check the error. Because if the
149 // device is null and this fails: you have an invalid device (so panic?) but if it
150 // succeeds, the device is no longer valid and we need to drop it. This is why this
151 // interface takes ownership of `self`.
152 sys::rs2_hardware_reset(self.device_ptr.as_ptr(), &mut err);
153 }
154 }
155
156 /// Gets the value associated with the provided camera info key from the device.
157 ///
158 /// Returns some information value associated with the camera info key if the `camera_info` is
159 /// supported by the device, else it returns `None`.
160 ///
161 pub fn info(&self, camera_info: Rs2CameraInfo) -> Option<&CStr> {
162 if !self.supports_info(camera_info) {
163 return None;
164 }
165
166 unsafe {
167 let mut err = std::ptr::null_mut::<sys::rs2_error>();
168
169 let val = sys::rs2_get_device_info(
170 self.device_ptr.as_ptr(),
171 #[allow(clippy::useless_conversion)]
172 (camera_info as i32).try_into().unwrap(),
173 &mut err,
174 );
175
176 if err.as_ref().is_none() {
177 Some(CStr::from_ptr(val))
178 } else {
179 sys::rs2_free_error(err);
180 None
181 }
182 }
183 }
184
185 /// Predicate for checking if `camera_info` is supported for this device.
186 ///
187 /// Returns true iff the device has a value associated with the `camera_info` key.
188 ///
189 pub fn supports_info(&self, camera_info: Rs2CameraInfo) -> bool {
190 unsafe {
191 let mut err = std::ptr::null_mut::<sys::rs2_error>();
192 let supports_info = sys::rs2_supports_device_info(
193 self.device_ptr.as_ptr(),
194 #[allow(clippy::useless_conversion)]
195 (camera_info as i32).try_into().unwrap(),
196 &mut err,
197 );
198
199 if err.as_ref().is_none() {
200 supports_info != 0
201 } else {
202 sys::rs2_free_error(err);
203 false
204 }
205 }
206 }
207
208 /// Get the underlying low-level pointer to the context object
209 ///
210 /// # Safety
211 ///
212 /// This method is not intended to be called or used outside of the crate itself. Be warned, it
213 /// is _undefined behaviour_ to delete or try to drop this pointer in any context. If you do,
214 /// you risk a double-free or use-after-free error.
215 pub(crate) unsafe fn get_raw(&self) -> NonNull<sys::rs2_device> {
216 self.device_ptr
217 }
218}