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
//! Configuration type for [Pipeline](crate::pipeline::Pipeline).

use crate::{
    error::{ErrorChecker, Result as RsResult},
    kind::{Format, StreamKind},
};
use std::{os::raw::c_int, ptr::NonNull};

/// The pipeline configuration that will be consumed by [Pipeline::start()](crate::pipeline::Pipeline::start).
#[derive(Debug)]
pub struct Config {
    pub(crate) ptr: NonNull<realsense_sys::rs2_config>,
}

impl Config {
    /// Create an instance.
    pub fn new() -> RsResult<Self> {
        let ptr = unsafe {
            let mut checker = ErrorChecker::new();
            let ptr = realsense_sys::rs2_create_config(checker.inner_mut_ptr());
            checker.check()?;
            ptr
        };
        let config = Self {
            ptr: NonNull::new(ptr).unwrap(),
        };
        Ok(config)
    }

    /// Enable data stream with attributes.
    pub fn enable_stream(
        self,
        stream: StreamKind,
        index: usize,
        width: usize,
        height: usize,
        format: Format,
        framerate: usize,
    ) -> RsResult<Self> {
        unsafe {
            let mut checker = ErrorChecker::new();
            let ptr = realsense_sys::rs2_config_enable_stream(
                self.ptr.as_ptr(),
                stream as realsense_sys::rs2_stream,
                index as c_int,
                width as c_int,
                height as c_int,
                format as realsense_sys::rs2_format,
                framerate as c_int,
                checker.inner_mut_ptr(),
            );
            checker.check()?;
            ptr
        };
        Ok(self)
    }
}

impl Drop for Config {
    fn drop(&mut self) {
        unsafe {
            realsense_sys::rs2_delete_config(self.ptr.as_ptr());
        }
    }
}

unsafe impl Send for Config {}