realsense_rust/
stream_profile.rs

1//! Types for representing data related to streams
2//!
3//! In librealsense2, a stream is an abstraction around a "sensor stream." In most applications,
4//! every sensor in the API will probably only have one stream that you actively care about (but
5//! not always!). That stream is tied to both the sensor it is configured on as well as the frames
6//! that are produced from the stream. The stream contains metadata such as the stream kind, the
7//! format of the incoming data, etc.
8//!
9//! There are two ways you can get streams in the system: from a stream profile list returned from
10//! the `Sensor`, or the frame stream from a frame type. In both cases the stream profile has an
11//! explicit lifetime that depends on the object you obtained it from. This is because stream
12//! profile ownership is not the same depending on how you obtained it.
13//!
14//! # Things to watch out for
15//!
16//! Extrinsics and intrinsics between different streams are obtained via the stream profile.
17//! However, your stream profile may not be valid if you get it from the frame. This is because
18//! stream profiles for the frame at a low level are owned by librealsense2. Calls to
19//! `rs2_get_frame_stream_profile` return a `*const rs2_stream_profile`, which is obtained by
20//! a call to C++ `shared_ptr::get()` internally to librealsense2. Since this is owned and managed
21//! by librealsense2, and calls to `shared_ptr::get()` aren't tracked by the internal ref-count on
22//! the `shared_ptr`, this means that the pointer could be invalidated at any time. In practice,
23//! this means that if you disconnect your device mid-way through streaming (i.e. yank the cable
24//! out), you could be holding onto a `StreamProfile` with an invalid internal pointer.
25//!
26//! We attempt to cache some aspects of the stream profile ahead of time, but in some cases this is
27//! not feasible (e.g. extrinsics). This is why some interfaces return `Result`s and others do not.
28//! The interfaces that do not return `Result` types are cached or otherwise safe-to-assume as
29//! such. The ones that do return `Result` types are will check the pointer at runtime and may
30//! return an error if it is no longer valid.
31//!
32//! We recommend that you get extrinsic or intrinsic information ahead of time when the device is
33//! connected (via `Device::sensor()` and then `Sensor::stream_profiles()`), rather than relying on
34//! the stream profile obtained via the frame types. The streams will have the same unique
35//! identifier if they correspond to the same stream.
36//!
37//! See [the `StreamProfile` type](crate::stream_profile::StreamProfile) for more information.
38
39use crate::{
40    base::{Rs2Extrinsics, Rs2Intrinsics, Rs2MotionDeviceIntrinsics},
41    check_rs2_error,
42    kind::{Rs2Exception, Rs2Format, Rs2StreamKind},
43};
44use anyhow::Result;
45use num_traits::FromPrimitive;
46use realsense_sys as sys;
47use std::{convert::TryFrom, mem::MaybeUninit, ptr::NonNull};
48use thiserror::Error;
49
50/// Type describing errors that can occur when trying to construct a stream profile.
51///
52/// Follows the standard pattern of errors where the enum variant describes what the low-level code
53/// was attempting to do while the string carried alongside describes the underlying error message
54/// from any C++ exceptions that occur.
55#[derive(Error, Debug)]
56pub enum StreamConstructionError {
57    /// Could not get stream data during construction.
58    #[error("Could not retrieve stream data. Type: {0}; Reason: {1}")]
59    CouldNotRetrieveStreamData(Rs2Exception, String),
60    /// Could not determine if this stream is the default stream during construction.
61    #[error("Could not determine if this is the default stream. Type: {0}; Reason: {1}")]
62    CouldNotDetermineIsDefault(Rs2Exception, String),
63    /// Could not get the stream profile from the stream profile list.
64    ///
65    /// Usually due to an internal exception of some kind.
66    #[error("Could not get the stream profile from a stream profile list. Type: {0}; Reason: {1}")]
67    CouldNotGetProfileFromList(Rs2Exception, String),
68    /// Could not clone the stream profile after acquiring it from the profile list.
69    #[error("Could not clone the stream profile after getting it from the profile list. Type: {0}; Reason: {1}")]
70    CouldNotCloneProfile(Rs2Exception, String),
71}
72
73/// Type describing errors in getting or setting stream-related data.
74///
75/// Follows the standard pattern of errors where the enum variant describes what the low-level code
76/// was attempting to do while the string carried alongside describes the underlying error message
77/// from any C++ exceptions that occur.
78#[derive(Error, Debug)]
79pub enum DataError {
80    /// Could not get extrinsics between the requested streams.
81    #[error("Could not get extrinsics. Type: {0}; Reason: {1}")]
82    CouldNotGetExtrinsics(Rs2Exception, String),
83    /// Could not set extrinsics between the requested streams.
84    #[error("Could not set extrinsics. Type: {0}; Reason: {1}")]
85    CouldNotSetExtrinsics(Rs2Exception, String),
86    /// This stream does not have video intrinsics.
87    #[error("Stream does not have video intrinsics")]
88    StreamDoesNotHaveVideoIntrinsics,
89    /// This stream does not have motion intrinsics.
90    #[error("Stream does not have motion intrinsics")]
91    StreamDoesNotHaveMotionIntrinsics,
92    /// Could not get video intrinsics from the requested stream.
93    #[error("Could not get video intrinsics. Type: {0}; Reason: {1}")]
94    CouldNotGetIntrinsics(Rs2Exception, String),
95    /// Could not get motion intrinsics from the requested stream.
96    #[error("Could not get motion intrinsics. Type: {0}; Reason: {1}")]
97    CouldNotGetMotionIntrinsics(Rs2Exception, String),
98}
99
100/// Type for holding the stream profile information.
101///
102/// This type exists as a high-level wrapper around an underlying `rs2_stream_profile` pointer. On
103/// construction, we cache a copy of the stream data and also cache whether or not this stream
104/// profile is the default stream for a sensor.
105///
106/// # Lifetimes
107///
108/// Stream profiles are acquired one of three ways:
109///
110/// 1. The stream profile list via the [`stream_profiles`](crate::sensor::Sensor::stream_profiles))
111///    method on the [`Sensor`](crate::sensor::Sensor) type.
112/// 2. The stream profile list via the
113///    [`streams`](crate::pipeline::PipelineProfile::streams) associated function on the
114///    [`PipelineProfile`](crate::pipeline::PipelineProfile) type.
115/// 3. The frame-specific `frame_stream_profile` member via the Frame type.
116///
117/// Stream profiles from the sensor can outlive the parent object that you obtain them from. In
118/// cases two and three above we return references to a stream profile owned by that type, so they
119/// may not.  In most cases you will probably want to grab the stream profile from the pipeline
120/// profile, which will give you all streams that are actively streaming from a given pipeline.
121#[derive(Debug)]
122pub struct StreamProfile {
123    // Underlying non-null pointer from realsense-sys.
124    //
125    // Unlike many other pointer types that we get from the ffi boundary, this pointer should not
126    // be manually deleted using `rs2_delete_stream_profile`. Streams are owned and managed by
127    // their corresponding sensor, which are owned and managed by their corresponding devices.
128    // Stream profile pointers should only be manually deleted if they are created by
129    /// `rs2_clone_stream_profile`, which we do not use in the high-level API.
130    ptr: NonNull<sys::rs2_stream_profile>,
131    /// The kind of stream (e.g. depth, video, accelerometer, gyroscope, etc.)
132    stream: Rs2StreamKind,
133    /// The bit format of the underlying data.
134    ///
135    /// For video streams this will describe how the pixels are packed and padded, for motion,
136    /// pose, and point frame streams this will describe how to deconstruct individual points or
137    /// observations.
138    format: Rs2Format,
139    /// The stream index. Useful if you wish to enable / disable certain streams by index.
140    index: usize,
141    /// The unique identifier for the stream.
142    unique_id: i32,
143    /// The framerate of the stream (how fast it outputs data)
144    framerate: i32,
145    /// Whether or not the stream is a default stream.
146    is_default: bool,
147    /// Whether or not to drop the profile
148    should_drop: bool,
149}
150
151impl TryFrom<NonNull<sys::rs2_stream_profile>> for StreamProfile {
152    type Error = StreamConstructionError;
153
154    /// Attempt to create a stream profile from a pointer to an `rs2_stream_profile` type.
155    ///
156    /// # Errors
157    ///
158    /// Returns [`StreamConstructionError::CouldNotRetrieveStreamData`] if the stream data
159    /// associated with this stream profile cannot be retrieved.
160    ///
161    /// Returns [`StreamConstructionError::CouldNotDetermineIsDefault`] if it cannot be determined
162    /// whether or not this stream is a default stream. This usually will only happen if the stream
163    /// is invalidated (e.g. due to a device disconnect) when you try to construct it.
164    fn try_from(stream_profile_ptr: NonNull<sys::rs2_stream_profile>) -> Result<Self, Self::Error> {
165        unsafe {
166            let mut err = std::ptr::null_mut::<sys::rs2_error>();
167
168            let mut stream = MaybeUninit::uninit();
169            let mut format = MaybeUninit::uninit();
170            let mut index = MaybeUninit::uninit();
171            let mut unique_id = MaybeUninit::uninit();
172            let mut framerate = MaybeUninit::uninit();
173
174            sys::rs2_get_stream_profile_data(
175                stream_profile_ptr.as_ptr(),
176                stream.as_mut_ptr(),
177                format.as_mut_ptr(),
178                index.as_mut_ptr(),
179                unique_id.as_mut_ptr(),
180                framerate.as_mut_ptr(),
181                &mut err,
182            );
183            check_rs2_error!(err, StreamConstructionError::CouldNotRetrieveStreamData)?;
184
185            let is_default =
186                sys::rs2_is_stream_profile_default(stream_profile_ptr.as_ptr(), &mut err);
187            check_rs2_error!(err, StreamConstructionError::CouldNotDetermineIsDefault)?;
188
189            Ok(StreamProfile {
190                ptr: stream_profile_ptr,
191                stream: Rs2StreamKind::from_i32(stream.assume_init() as i32).unwrap(),
192                format: Rs2Format::from_i32(format.assume_init() as i32).unwrap(),
193                index: index.assume_init() as usize,
194                unique_id: unique_id.assume_init(),
195                framerate: framerate.assume_init(),
196                is_default: is_default != 0,
197                should_drop: false,
198            })
199        }
200    }
201}
202
203impl Drop for StreamProfile {
204    fn drop(&mut self) {
205        unsafe {
206            if self.should_drop {
207                sys::rs2_delete_stream_profile(self.ptr.as_ptr());
208            }
209        }
210    }
211}
212
213impl StreamProfile {
214    /// Attempt to construct a stream profile from a profile list and index.
215    ///
216    /// Constructs a new stream profile from the list and index, or returns an error.
217    ///
218    /// # Errors
219    ///
220    /// Returns [`StreamConstructionError::CouldNotGetProfileFromList`] if the stream profile
221    /// cannot be acquired from the profile list. (e.g. index is invalid).
222    ///
223    /// Returns [`StreamConstructionError::CouldNotRetrieveStreamData`] if the stream data
224    /// associated with this stream profile cannot be retrieved.
225    ///
226    /// Returns [`StreamConstructionError::CouldNotDetermineIsDefault`] if it cannot be determined
227    /// whether or not this stream is a default stream. This usually will only happen if the stream
228    /// is invalidated (e.g. due to a device disconnect) when you try to construct it.
229    pub(crate) fn try_create(
230        profiles: &NonNull<sys::rs2_stream_profile_list>,
231        index: i32,
232    ) -> Result<Self, StreamConstructionError> {
233        unsafe {
234            let mut err = std::ptr::null_mut::<sys::rs2_error>();
235            let profile_ptr = sys::rs2_get_stream_profile(profiles.as_ptr(), index, &mut err);
236            check_rs2_error!(err, StreamConstructionError::CouldNotGetProfileFromList)?;
237
238            let mut stream = MaybeUninit::uninit();
239            let mut format = MaybeUninit::uninit();
240            let mut index = MaybeUninit::uninit();
241            let mut unique_id = MaybeUninit::uninit();
242            let mut framerate = MaybeUninit::uninit();
243
244            sys::rs2_get_stream_profile_data(
245                profile_ptr,
246                stream.as_mut_ptr(),
247                format.as_mut_ptr(),
248                index.as_mut_ptr(),
249                unique_id.as_mut_ptr(),
250                framerate.as_mut_ptr(),
251                &mut err,
252            );
253            check_rs2_error!(err, StreamConstructionError::CouldNotRetrieveStreamData)?;
254
255            let profile_ptr = sys::rs2_clone_stream_profile(
256                profile_ptr,
257                stream.assume_init(),
258                index.assume_init(),
259                format.assume_init(),
260                &mut err,
261            );
262            check_rs2_error!(err, StreamConstructionError::CouldNotCloneProfile)?;
263
264            let nonnull_profile_ptr = NonNull::new(profile_ptr).unwrap();
265            let mut stream_profile = Self::try_from(nonnull_profile_ptr)?;
266            stream_profile.should_drop = true;
267
268            Ok(stream_profile)
269        }
270    }
271
272    /// Predicate for whether or not the stream is a default stream.
273    #[inline]
274    pub fn is_default(&self) -> bool {
275        self.is_default
276    }
277
278    /// Gets the stream kind from the stream data.
279    ///
280    /// This can be e.g. Depth, Video, Accel, Gyro, etc.
281    #[inline]
282    pub fn kind(&self) -> Rs2StreamKind {
283        self.stream
284    }
285
286    /// Gets the format for the underlying data.
287    ///
288    /// For video streams this will describe how the pixels are packed and padded, for motion,
289    /// pose, and point frame streams this will describe how to deconstruct individual points or
290    /// observations.
291    #[inline]
292    pub fn format(&self) -> Rs2Format {
293        self.format
294    }
295
296    /// Gets the stream's index.
297    ///
298    /// This is useful if you want to enable / disable a particular stream according to its index.
299    #[inline]
300    pub fn index(&self) -> usize {
301        self.index
302    }
303
304    /// Gets the stream's unique identifier.
305    #[inline]
306    pub fn unique_id(&self) -> i32 {
307        self.unique_id
308    }
309
310    /// Gets the framerate / data rate of frames generated by the stream.
311    #[inline]
312    pub fn framerate(&self) -> i32 {
313        self.framerate
314    }
315
316    /// Get extrinsics between the origin stream (`self`) and target stream (`to_profile`).
317    ///
318    /// Returns the extrinsics between the origin and target streams from the underlying realsense
319    /// driver iff both underlying stream pointers are valid and extrinsics exist. Otherwise
320    /// returns an error.
321    ///
322    /// # Errors
323    ///
324    /// Returns [`DataError::CouldNotGetExtrinsics`] if this call fails for whatever reason.
325    pub fn extrinsics(&self, to_profile: &StreamProfile) -> Result<Rs2Extrinsics, DataError> {
326        unsafe {
327            let mut err = std::ptr::null_mut::<sys::rs2_error>();
328            let mut extrinsics = MaybeUninit::<sys::rs2_extrinsics>::uninit();
329
330            sys::rs2_get_extrinsics(
331                self.ptr.as_ptr(),
332                to_profile.ptr.as_ptr(),
333                extrinsics.as_mut_ptr(),
334                &mut err,
335            );
336            check_rs2_error!(err, DataError::CouldNotGetExtrinsics)?;
337
338            Ok(Rs2Extrinsics(extrinsics.assume_init()))
339        }
340    }
341
342    /// Set `extrinsics` between the origin stream (`self`) and target stream (`to_profile`).
343    ///
344    /// Returns null tuple `()` iff the streams are valid and the extrinsics are successfully set.
345    /// Otherwise returns an error.
346    ///
347    /// # Errors
348    ///
349    /// Returns [`DataError::CouldNotSetExtrinsics`] if this call fails for whatever reason.
350    pub fn set_extrinsics(
351        &self,
352        to_profile: &StreamProfile,
353        extrinsics: Rs2Extrinsics,
354    ) -> Result<(), DataError> {
355        unsafe {
356            let mut err = std::ptr::null_mut::<sys::rs2_error>();
357            sys::rs2_register_extrinsics(
358                self.ptr.as_ptr(),
359                to_profile.ptr.as_ptr(),
360                extrinsics.0,
361                &mut err,
362            );
363            check_rs2_error!(err, DataError::CouldNotSetExtrinsics)?;
364
365            Ok(())
366        }
367    }
368
369    /// Get video intrinsics from the stream.
370    ///
371    /// Returns a set of video intrinsics for the stream iff the stream has video intrinsics and the stream
372    /// pointer is valid. Otherwise returns an error.
373    ///
374    /// # Errors
375    ///
376    /// Returns [`DataError::StreamDoesNotHaveVideoIntrinsics`] if the stream does not have video
377    /// intrinsics.
378    ///
379    /// Returns [`DataError::CouldNotGetIntrinsics`] if this call fails for any other reason.
380    pub fn intrinsics(&self) -> Result<Rs2Intrinsics, DataError> {
381        match self.stream {
382            Rs2StreamKind::Depth => (),
383            Rs2StreamKind::Color => (),
384            Rs2StreamKind::Infrared => (),
385            Rs2StreamKind::Fisheye => (),
386            _ => {
387                return Err(DataError::StreamDoesNotHaveVideoIntrinsics);
388            }
389        }
390        unsafe {
391            let mut err = std::ptr::null_mut::<sys::rs2_error>();
392            let mut intrinsics = MaybeUninit::<sys::rs2_intrinsics>::uninit();
393
394            sys::rs2_get_video_stream_intrinsics(
395                self.ptr.as_ptr(),
396                intrinsics.as_mut_ptr(),
397                &mut err,
398            );
399            check_rs2_error!(err, DataError::CouldNotGetIntrinsics)?;
400
401            Ok(Rs2Intrinsics(intrinsics.assume_init()))
402        }
403    }
404
405    /// Get motion intrinsics from the stream.
406    ///
407    /// Returns a set of motion device intrinsics for the stream iff the stream has motion device
408    /// intrinsics and the stream pointer is valid. Otherwise returns an error.
409    ///
410    /// # Errors
411    ///
412    /// Returns
413    /// [`DataError::StreamDoesNotHaveMotionIntrinsics`](DataError::StreamDoesNotHaveMotionIntrinsics)
414    /// if the stream does not have motion intrinsics.
415    ///
416    /// Returns [`DataError::CouldNotGetMotionIntrinsics`](DataError::CouldNotGetMotionIntrinsics)
417    /// if this call fails for any other reason.
418    pub fn motion_intrinsics(&self) -> Result<Rs2MotionDeviceIntrinsics, DataError> {
419        match self.stream {
420            Rs2StreamKind::Gyro => (),
421            Rs2StreamKind::Accel => (),
422            _ => {
423                return Err(DataError::StreamDoesNotHaveMotionIntrinsics);
424            }
425        }
426        unsafe {
427            let mut err = std::ptr::null_mut::<sys::rs2_error>();
428            let mut intrinsics = MaybeUninit::<sys::rs2_motion_device_intrinsic>::uninit();
429
430            sys::rs2_get_motion_intrinsics(self.ptr.as_ptr(), intrinsics.as_mut_ptr(), &mut err);
431            check_rs2_error!(err, DataError::CouldNotGetMotionIntrinsics)?;
432
433            Ok(Rs2MotionDeviceIntrinsics(intrinsics.assume_init()))
434        }
435    }
436}