realsense_rust/config.rs
1//! A type representing the [`Pipeline`](crate::pipeline::InactivePipeline) configuration.
2
3use crate::{
4 base::from_path,
5 check_rs2_error,
6 kind::{Rs2Exception, Rs2Format, Rs2StreamKind},
7};
8use anyhow::Result;
9use realsense_sys as sys;
10use std::{convert::TryInto, ffi::CStr, path::Path, ptr::NonNull};
11use thiserror::Error;
12
13/// Type describing all possible errors that can occur when trying to configure a pipeline.
14#[derive(Error, Debug)]
15pub enum ConfigurationError {
16 /// The requested stream could not be enabled.
17 #[error("Could not enable stream. Type: {0}; Reason: {1}")]
18 CouldNotEnableStream(Rs2Exception, String),
19 /// All streams could not be enabled.
20 #[error("Could not enable all streams. Type: {0}; Reason: {1}")]
21 CouldNotEnableAllStreams(Rs2Exception, String),
22 /// The requested stream could not be disabled.
23 #[error("Could not disable stream. Type: {0}; Reason: {1}")]
24 CouldNotDisableStream(Rs2Exception, String),
25 /// All streams could not be enabled.
26 #[error("Could not disable all streams. Type: {0}; Reason: {1}")]
27 CouldNotDisableAllStreams(Rs2Exception, String),
28 /// The specified device could not be enabled.
29 #[error("Could not enable requested device. Type: {0}; Reason: {1}")]
30 CouldNotEnableDevice(Rs2Exception, String),
31 /// Recording to file could not be enabled for the specified device.
32 #[error("Could not enable recording to file from device. Type: {0}; Reason: {1}")]
33 CouldNotEnableRecordingToFile(Rs2Exception, String),
34}
35
36/// Type representing the [`Pipeline`](crate::pipeline::InactivePipeline) configuration.
37#[derive(Debug)]
38pub struct Config {
39 /// A non-null pointer to the underlying librealsense2 configuration.
40 config_ptr: NonNull<sys::rs2_config>,
41}
42
43impl Drop for Config {
44 fn drop(&mut self) {
45 unsafe {
46 sys::rs2_delete_config(self.config_ptr.as_ptr());
47 }
48 }
49}
50
51unsafe impl Send for Config {}
52
53impl Default for Config {
54 fn default() -> Self {
55 Self::new()
56 }
57}
58
59impl Config {
60 /// Construct a new configuration.
61 pub fn new() -> Self {
62 unsafe {
63 let mut err = std::ptr::null_mut::<sys::rs2_error>();
64 let ptr = sys::rs2_create_config(&mut err);
65
66 // Literally the only way this can fail seems to be through C++ make_shared.
67 //
68 // This would imply that OOM errors are the only possible exceptions here, so I'm
69 // inclined to believe that checking the error is a fool's errand: If this call errors
70 // there isn't going to be a whole lot you can do.
71 //
72 // We're better off letting Rust panic due to NonNull::new(ptr).unwrap() than to add
73 // any extra logic on top.
74
75 Self {
76 config_ptr: NonNull::new(ptr).unwrap(),
77 }
78 }
79 }
80
81 /// Enable the stream of kind `stream` with the provided attributes.
82 ///
83 /// Returns a mutable reference to self, or a configuration error if the underlying FFI call
84 /// fails.
85 ///
86 /// # Arguments
87 ///
88 /// It is not an error if `stream` and `format` do not match appropriately, but you may find
89 /// that the configuration will never resolve if they do not.. E.g. you cannot pass in
90 /// [`Rs2StreamKind::Color`] alongside [`Rs2Format::Z16`]. If you're unsure, pass in
91 /// [`Rs2Format::Any`] and librealsense2 will determine what the most appropriate format is for
92 /// a given stream.
93 ///
94 /// The index is can be optionally provided. If it is not provided, then librealsense2 will
95 /// pick the most suitable stream index it can find.
96 ///
97 /// If either `width` or `height` (but not both) are zero, librealsense2 will find the most
98 /// appropriate value to match the non-zero one. E.g. if `width` is 640 and `height` is 0, then
99 /// librealsense2 will return 640x480 images (the closest appropriate format).
100 ///
101 /// # Errors
102 ///
103 /// Returns [`ConfigurationError::CouldNotEnableStream`] if any internal exceptions occur while
104 /// making this call. Note that this does not independently check the values passed into each
105 /// of the provided arguments / attributes. If those are invalid, they will be checked when you
106 /// call [`InactivePipeline::start`](crate::pipeline::InactivePipeline::start) or
107 /// [`InactivePipeline::resolve`](crate::pipeline::InactivePipeline::resolve).
108 ///
109 pub fn enable_stream(
110 &mut self,
111 stream: Rs2StreamKind,
112 index: Option<usize>,
113 width: usize,
114 height: usize,
115 format: Rs2Format,
116 framerate: usize,
117 ) -> Result<&mut Self, ConfigurationError> {
118 let index: i32 = if let Some(i) = index { i as i32 } else { -1 };
119 unsafe {
120 let mut err = std::ptr::null_mut::<sys::rs2_error>();
121 sys::rs2_config_enable_stream(
122 self.config_ptr.as_ptr(),
123 #[allow(clippy::useless_conversion)]
124 (stream as i32).try_into().unwrap(),
125 index,
126 width as i32,
127 height as i32,
128 #[allow(clippy::useless_conversion)]
129 (format as i32).try_into().unwrap(),
130 framerate as i32,
131 &mut err,
132 );
133 check_rs2_error!(err, ConfigurationError::CouldNotEnableStream)?;
134 };
135 Ok(self)
136 }
137
138 /// Enable all device streams explicitly.
139 ///
140 /// This enables all streams with the default configuration. What this means is that
141 /// librealsense2 will pick the format, resolution, and framerate. If you want to specify
142 /// those values yourself, see [`Config::enable_stream`].
143 ///
144 /// Returns a mutable reference to self if it succeeds or a configuration error.
145 ///
146 /// # Errors
147 ///
148 /// Returns [`ConfigurationError::CouldNotEnableAllStreams`] if this call fails for whatever
149 /// reason.
150 ///
151 pub fn enable_all_streams(&mut self) -> Result<&mut Self, ConfigurationError> {
152 unsafe {
153 let mut err = std::ptr::null_mut::<sys::rs2_error>();
154 sys::rs2_config_enable_all_stream(self.config_ptr.as_ptr(), &mut err);
155 check_rs2_error!(err, ConfigurationError::CouldNotEnableAllStreams)?;
156 }
157 Ok(self)
158 }
159
160 /// Enable device from a serial number.
161 ///
162 /// This is useful if you want to mandate that your configuration is only applied to a device
163 /// with a specific serial number. The serial can be obtained from the
164 /// [`Device`](crate::device::Device::info) method by passing in
165 /// [`Rs2CameraInfo::SerialNumber`](crate::kind::Rs2CameraInfo::SerialNumber).
166 ///
167 /// Returns a mutable reference to self if it succeeds or a configuration error.
168 ///
169 /// # Errors
170 ///
171 /// Returns [`ConfigurationError::CouldNotEnableDevice`] if the device could not be enabled.
172 ///
173 pub fn enable_device_from_serial(
174 &mut self,
175 serial: &CStr,
176 ) -> Result<&mut Self, ConfigurationError> {
177 unsafe {
178 let mut err = std::ptr::null_mut::<sys::rs2_error>();
179 sys::rs2_config_enable_device(self.config_ptr.as_ptr(), serial.as_ptr(), &mut err);
180 check_rs2_error!(err, ConfigurationError::CouldNotEnableDevice)?;
181 }
182 Ok(self)
183 }
184
185 /// Enable device from a file path.
186 ///
187 /// Enables a virtual "device" whose observations have been recorded to a file. If
188 /// `loop_playback` is true, then the device will continue to stream observations once it has
189 /// reached the end of the file by continuously looping back to the first observations in the
190 /// serialized streams.
191 ///
192 /// Returns a mutable reference to self if it succeeds or a configuration error.
193 ///
194 /// # Errors
195 ///
196 /// Returns [`NulError`](std::ffi::NulError) if the provided file path cannot be cleanly
197 /// represented as a [`CString`](std::ffi::CString). This usually only occurs if you have null
198 /// characters in the path. Constructing a path using the utilties in Rust's [`std::fs`] are
199 /// expected to work.
200 ///
201 /// Returns a [`ConfigurationError::CouldNotEnableDevice`] if the device cannot be enabled for
202 /// any reason. e.g. if your `file` is valid and can be converted into a `CString`, but is
203 /// actually a path to a directory, you'll likely see an error here.
204 ///
205 pub fn enable_device_from_file<P>(&mut self, file: P, loop_playback: bool) -> Result<&mut Self>
206 where
207 P: AsRef<Path>,
208 {
209 let path = from_path(file)?;
210 unsafe {
211 let mut err = std::ptr::null_mut::<sys::rs2_error>();
212 sys::rs2_config_enable_device_from_file_repeat_option(
213 self.config_ptr.as_ptr(),
214 path.as_ptr(),
215 loop_playback as i32,
216 &mut err,
217 );
218 check_rs2_error!(err, ConfigurationError::CouldNotEnableDevice)?;
219 }
220 Ok(self)
221 }
222
223 /// Enable recording data streams to file.
224 ///
225 /// Configuration option for writing / serializing data from the pipeline to a file. This
226 /// happens independently of any frame delivery once the pipeline has been started. It is an
227 /// error if you attempt to record to file if you are streaming from a file (see
228 /// [`Config::enable_device_from_file`]).
229 ///
230 /// Returns a mutable reference to self if it succeeds or an error.
231 ///
232 /// # Errors
233 ///
234 /// Returns [`NulError`](std::ffi::NulError) if the provided file path cannot be cleanly
235 /// represented as a [`CString`](std::ffi::CString). This usually only occurs if you have null
236 /// characters in the path. Constructing a path using the utilties in Rust's [`std::fs`] are
237 /// expected to work.
238 ///
239 /// Returns [`ConfigurationError::CouldNotEnableRecordingToFile`] if the path is not a valid
240 /// path to a file or if you are trying to record to a file while streaming from a file.
241 ///
242 pub fn enable_record_to_file<P>(&mut self, file: P) -> Result<&mut Self>
243 where
244 P: AsRef<Path>,
245 {
246 let path = from_path(file)?;
247 unsafe {
248 let mut err = std::ptr::null_mut::<sys::rs2_error>();
249 sys::rs2_config_enable_record_to_file(
250 self.config_ptr.as_ptr(),
251 path.as_ptr(),
252 &mut err,
253 );
254 check_rs2_error!(err, ConfigurationError::CouldNotEnableRecordingToFile)?;
255 }
256 Ok(self)
257 }
258
259 /// Disable a specific data stream by stream index.
260 ///
261 /// Returns a mutable reference to self or a configuration error.
262 ///
263 /// # Errors
264 ///
265 /// Returns [`ConfigurationError::CouldNotDisableStream`] if the stream cannot be disabled.
266 ///
267 pub fn disable_stream_at_index(
268 &mut self,
269 stream: Rs2StreamKind,
270 index: usize,
271 ) -> Result<&mut Self, ConfigurationError> {
272 unsafe {
273 let mut err = std::ptr::null_mut::<sys::rs2_error>();
274 sys::rs2_config_disable_indexed_stream(
275 self.config_ptr.as_ptr(),
276 #[allow(clippy::useless_conversion)]
277 (stream as i32).try_into().unwrap(),
278 index as i32,
279 &mut err,
280 );
281 check_rs2_error!(err, ConfigurationError::CouldNotDisableStream)?;
282 }
283 Ok(self)
284 }
285
286 /// Disable data stream by stream kind.
287 ///
288 /// This method removes the first stream of the given `stream` kind.
289 ///
290 /// Returns a mutable reference to self or a configuration error.
291 ///
292 /// # Errors
293 ///
294 /// Returns [`ConfigurationError::CouldNotDisableStream`] if the stream cannot be disabled.
295 ///
296 pub fn disable_stream(
297 &mut self,
298 stream: Rs2StreamKind,
299 ) -> Result<&mut Self, ConfigurationError> {
300 unsafe {
301 let mut err = std::ptr::null_mut::<sys::rs2_error>();
302 sys::rs2_config_disable_stream(
303 self.config_ptr.as_ptr(),
304 #[allow(clippy::useless_conversion)]
305 (stream as i32).try_into().unwrap(),
306 &mut err,
307 );
308 check_rs2_error!(err, ConfigurationError::CouldNotDisableStream)?;
309 }
310 Ok(self)
311 }
312
313 /// Disable all device streams explicitly.
314 ///
315 /// This method disables every stream.
316 ///
317 /// Returns a mutable reference to self or a configuration error.
318 ///
319 /// # Errors
320 ///
321 /// Returns [`ConfigurationError::CouldNotDisableAllStreams`] if the streams cannot be
322 /// disabled.
323 ///
324 pub fn disable_all_streams(&mut self) -> Result<&mut Self, ConfigurationError> {
325 unsafe {
326 let mut err = std::ptr::null_mut::<sys::rs2_error>();
327 sys::rs2_config_disable_all_streams(self.config_ptr.as_ptr(), &mut err);
328 check_rs2_error!(err, ConfigurationError::CouldNotDisableAllStreams)?;
329 }
330 Ok(self)
331 }
332
333 /// Get the underlying low-level pointer to the configuration object.
334 ///
335 /// # Safety
336 ///
337 /// This method is not intended to be called or used outside of the crate itself. Be warned, it
338 /// is _undefined behaviour_ to call [`realsense_sys::rs2_delete_config`] on this pointer. If
339 /// you do, you risk a double-free error when the [`Config`] struct itself is dropped.
340 ///
341 pub(crate) unsafe fn get_raw(&self) -> NonNull<sys::rs2_config> {
342 self.config_ptr
343 }
344}