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`](crate::kind::Rs2StreamKind::Color) alongside
91 /// [`Rs2Format::Z16`](crate::kind::Rs2Format::Z16). If you're unsure, pass in
92 /// [`Rs2Format::Any`](crate::kind::Rs2Format::Any) and librealsense2 will determine what the
93 /// most appropriate format is for a given stream.
94 ///
95 /// The index is can be optionally provided. If it is not provided, then librealsense2 will
96 /// pick the most suitable stream index it can find.
97 ///
98 /// If either `width` or `height` (but not both) are zero, librealsense2 will find the most
99 /// appropriate value to match the non-zero one. E.g. if `width` is 640 and `height` is 0, then
100 /// librealsense2 will return 640x480 images (the closest appropriate format).
101 ///
102 /// # Errors
103 ///
104 /// Returns [`ConfigurationError::CouldNotEnableStream`] if any internal exceptions occur while
105 /// making this call. Note that this does not independently check the values passed into each
106 /// of the provided arguments / attributes. If those are invalid, they will be checked when you
107 /// call [`InactivePipeline::start`](crate::pipeline::InactivePipeline::start) or
108 /// [`InactivePipeline::resolve`](crate::pipeline::InactivePipeline::resolve).
109 ///
110 pub fn enable_stream(
111 &mut self,
112 stream: Rs2StreamKind,
113 index: Option<usize>,
114 width: usize,
115 height: usize,
116 format: Rs2Format,
117 framerate: usize,
118 ) -> Result<&mut Self, ConfigurationError> {
119 let index: i32 = if let Some(i) = index { i as i32 } else { -1 };
120 unsafe {
121 let mut err = std::ptr::null_mut::<sys::rs2_error>();
122 sys::rs2_config_enable_stream(
123 self.config_ptr.as_ptr(),
124 #[allow(clippy::useless_conversion)]
125 (stream as i32).try_into().unwrap(),
126 index,
127 width as i32,
128 height as i32,
129 #[allow(clippy::useless_conversion)]
130 (format as i32).try_into().unwrap(),
131 framerate as i32,
132 &mut err,
133 );
134 check_rs2_error!(err, ConfigurationError::CouldNotEnableStream)?;
135 };
136 Ok(self)
137 }
138
139 /// Enable all device streams explicitly.
140 ///
141 /// This enables all streams with the default configuration. What this means is that
142 /// librealsense2 will pick the format, resolution, and framerate. If you want to specify
143 /// those values yourself, see [`Config::enable_stream`].
144 ///
145 /// Returns a mutable reference to self if it succeeds or a configuration error.
146 ///
147 /// # Errors
148 ///
149 /// Returns [`ConfigurationError::CouldNotEnableAllStreams`] if this call fails for whatever
150 /// reason.
151 ///
152 pub fn enable_all_streams(&mut self) -> Result<&mut Self, ConfigurationError> {
153 unsafe {
154 let mut err = std::ptr::null_mut::<sys::rs2_error>();
155 sys::rs2_config_enable_all_stream(self.config_ptr.as_ptr(), &mut err);
156 check_rs2_error!(err, ConfigurationError::CouldNotEnableAllStreams)?;
157 }
158 Ok(self)
159 }
160
161 /// Enable device from a serial number.
162 ///
163 /// This is useful if you want to mandate that your configuration is only applied to a device
164 /// with a specific serial number. The serial can be obtained from the
165 /// [`Device`](crate::device::Device::info) method by passing in
166 /// [`Rs2CameraInfo::SerialNumber`](crate::kind::Rs2CameraInfo::SerialNumber).
167 ///
168 /// Returns a mutable reference to self if it succeeds or a configuration error.
169 ///
170 /// # Errors
171 ///
172 /// Returns [`ConfigurationError::CouldNotEnableDevice`] if the device could not be enabled.
173 ///
174 pub fn enable_device_from_serial(
175 &mut self,
176 serial: &CStr,
177 ) -> Result<&mut Self, ConfigurationError> {
178 unsafe {
179 let mut err = std::ptr::null_mut::<sys::rs2_error>();
180 sys::rs2_config_enable_device(self.config_ptr.as_ptr(), serial.as_ptr(), &mut err);
181 check_rs2_error!(err, ConfigurationError::CouldNotEnableDevice)?;
182 }
183 Ok(self)
184 }
185
186 /// Enable device from a file path.
187 ///
188 /// Enables a virtual "device" whose observations have been recorded to a file. If
189 /// `loop_playback` is true, then the device will continue to stream observations once it has
190 /// reached the end of the file by continuously looping back to the first observations in the
191 /// serialized streams.
192 ///
193 /// Returns a mutable reference to self if it succeeds or a configuration error.
194 ///
195 /// # Errors
196 ///
197 /// Returns [`NulError`](std::ffi::NulError) if the provided file path cannot be cleanly
198 /// represented as a [`CString`](std::ffi::CString). This usually only occurs if you have null
199 /// characters in the path. Constructing a path using the utilties in Rust's [`std::fs`] are
200 /// expected to work.
201 ///
202 /// Returns a [`ConfigurationError::CouldNotEnableDevice`] if the device cannot be enabled for
203 /// any reason. e.g. if your `file` is valid and can be converted into a `CString`, but is
204 /// actually a path to a directory, you'll likely see an error here.
205 ///
206 pub fn enable_device_from_file<P>(&mut self, file: P, loop_playback: bool) -> Result<&mut Self>
207 where
208 P: AsRef<Path>,
209 {
210 let path = from_path(file)?;
211 unsafe {
212 let mut err = std::ptr::null_mut::<sys::rs2_error>();
213 sys::rs2_config_enable_device_from_file_repeat_option(
214 self.config_ptr.as_ptr(),
215 path.as_ptr(),
216 loop_playback as i32,
217 &mut err,
218 );
219 check_rs2_error!(err, ConfigurationError::CouldNotEnableDevice)?;
220 }
221 Ok(self)
222 }
223
224 /// Enable recording data streams to file.
225 ///
226 /// Configuration option for writing / serializing data from the pipeline to a file. This
227 /// happens independently of any frame delivery once the pipeline has been started. It is an
228 /// error if you attempt to record to file if you are streaming from a file (see
229 /// [`Config::enable_device_from_file`]).
230 ///
231 /// Returns a mutable reference to self if it succeeds or an error.
232 ///
233 /// # Errors
234 ///
235 /// Returns [`NulError`](std::ffi::NulError) if the provided file path cannot be cleanly
236 /// represented as a [`CString`](std::ffi::CString). This usually only occurs if you have null
237 /// characters in the path. Constructing a path using the utilties in Rust's [`std::fs`] are
238 /// expected to work.
239 ///
240 /// Returns [`ConfigurationError::CouldNotEnableRecordingToFile`] if the path is not a valid
241 /// path to a file or if you are trying to record to a file while streaming from a file.
242 ///
243 pub fn enable_record_to_file<P>(&mut self, file: P) -> Result<&mut Self>
244 where
245 P: AsRef<Path>,
246 {
247 let path = from_path(file)?;
248 unsafe {
249 let mut err = std::ptr::null_mut::<sys::rs2_error>();
250 sys::rs2_config_enable_record_to_file(
251 self.config_ptr.as_ptr(),
252 path.as_ptr(),
253 &mut err,
254 );
255 check_rs2_error!(err, ConfigurationError::CouldNotEnableRecordingToFile)?;
256 }
257 Ok(self)
258 }
259
260 /// Disable a specific data stream by stream index.
261 ///
262 /// Returns a mutable reference to self or a configuration error.
263 ///
264 /// # Errors
265 ///
266 /// Returns [`ConfigurationError::CouldNotDisableStream`] if the stream cannot be disabled.
267 ///
268 pub fn disable_stream_at_index(
269 &mut self,
270 stream: Rs2StreamKind,
271 index: usize,
272 ) -> Result<&mut Self, ConfigurationError> {
273 unsafe {
274 let mut err = std::ptr::null_mut::<sys::rs2_error>();
275 sys::rs2_config_disable_indexed_stream(
276 self.config_ptr.as_ptr(),
277 #[allow(clippy::useless_conversion)]
278 (stream as i32).try_into().unwrap(),
279 index as i32,
280 &mut err,
281 );
282 check_rs2_error!(err, ConfigurationError::CouldNotDisableStream)?;
283 }
284 Ok(self)
285 }
286
287 /// Disable data stream by stream kind.
288 ///
289 /// This method removes the first stream of the given `stream` kind.
290 ///
291 /// Returns a mutable reference to self or a configuration error.
292 ///
293 /// # Errors
294 ///
295 /// Returns [`ConfigurationError::CouldNotDisableStream`] if the stream cannot be disabled.
296 ///
297 pub fn disable_stream(
298 &mut self,
299 stream: Rs2StreamKind,
300 ) -> Result<&mut Self, ConfigurationError> {
301 unsafe {
302 let mut err = std::ptr::null_mut::<sys::rs2_error>();
303 sys::rs2_config_disable_stream(
304 self.config_ptr.as_ptr(),
305 #[allow(clippy::useless_conversion)]
306 (stream as i32).try_into().unwrap(),
307 &mut err,
308 );
309 check_rs2_error!(err, ConfigurationError::CouldNotDisableStream)?;
310 }
311 Ok(self)
312 }
313
314 /// Disable all device streams explicitly.
315 ///
316 /// This method disables every stream.
317 ///
318 /// Returns a mutable reference to self or a configuration error.
319 ///
320 /// # Errors
321 ///
322 /// Returns [`ConfigurationError::CouldNotDisableAllStreams`] if the streams cannot be
323 /// disabled.
324 ///
325 pub fn disable_all_streams(&mut self) -> Result<&mut Self, ConfigurationError> {
326 unsafe {
327 let mut err = std::ptr::null_mut::<sys::rs2_error>();
328 sys::rs2_config_disable_all_streams(self.config_ptr.as_ptr(), &mut err);
329 check_rs2_error!(err, ConfigurationError::CouldNotDisableAllStreams)?;
330 }
331 Ok(self)
332 }
333
334 /// Get the underlying low-level pointer to the configuration object.
335 ///
336 /// # Safety
337 ///
338 /// This method is not intended to be called or used outside of the crate itself. Be warned, it
339 /// is _undefined behaviour_ to call [`realsense_sys::rs2_delete_config`] on this pointer. If
340 /// you do, you risk a double-free error when the [`Config`] struct itself is dropped.
341 ///
342 pub(crate) unsafe fn get_raw(&self) -> NonNull<sys::rs2_config> {
343 self.config_ptr
344 }
345}