realsense_rust/kind/format.rs
1//! Enumeration of frame data format & layout
2
3use num_derive::{FromPrimitive, ToPrimitive};
4use realsense_sys as sys;
5
6/// A type representing all possible data formats for raw frame data
7#[repr(i32)]
8#[derive(FromPrimitive, ToPrimitive, Debug, Clone, Copy, PartialEq, Eq, Hash)]
9pub enum Rs2Format {
10 /// Format key used to tell librealsense2 to pick the best suited format.
11 ///
12 /// Unlike the other format entries in this enum, `Any` is used primarily when setting up
13 /// streams in the config / pipeline. If you pass this, librealsense2 will pick the best suited
14 /// (default) format for a given sensor.
15 Any = sys::rs2_format_RS2_FORMAT_ANY as i32,
16 /// 32-bit y0, u, y1, v data for every two pixels.
17 ///
18 /// Similar to YUV422 but packed in a different order. See [the wikipedia
19 /// page](https://en.wikipedia.org/wiki/YUV) for more info.
20 Yuyv = sys::rs2_format_RS2_FORMAT_YUYV as i32,
21 /// 32-bit u, y0, v, y1 data for every two pixels.
22 ///
23 /// Similar to the standard YUYV pixel format, but packed in a different order
24 Uyvy = sys::rs2_format_RS2_FORMAT_UYVY as i32,
25 /// Raw data from the motion sensor
26 MotionRaw = sys::rs2_format_RS2_FORMAT_MOTION_RAW as i32,
27 /// Raw data from the external sensors hooked to one of the GPIO pins
28 GpioRaw = sys::rs2_format_RS2_FORMAT_GPIO_RAW as i32,
29 /// 32-bit floating point depth distance value
30 Distance = sys::rs2_format_RS2_FORMAT_DISTANCE as i32,
31 /// Bitstream encoding for video in which an image of each frame is encoded as JPEG-DIB
32 Mjpeg = sys::rs2_format_RS2_FORMAT_MJPEG as i32,
33 /// Multi-planar 16-bit depth + 10-bit IR
34 Inzi = sys::rs2_format_RS2_FORMAT_INZI as i32,
35 /// 8-bit IR stream
36 Invi = sys::rs2_format_RS2_FORMAT_INVI as i32,
37 /// Pose data packed as array of 32-bit floats.
38 ///
39 /// Contains translation vector, rotation quaternion, prediction velocities, and accelerations
40 /// vectors.
41 ///
42 _6Dof = sys::rs2_format_RS2_FORMAT_6DOF as i32,
43 /// 8-bit blue, green, and red channels (in that order)
44 Bgr8 = sys::rs2_format_RS2_FORMAT_BGR8 as i32,
45 /// 8-bit blue, green, red, and alpha channels (in that order)
46 ///
47 /// Alpha channel is always equal to 0xFF
48 Bgra8 = sys::rs2_format_RS2_FORMAT_BGRA8 as i32,
49 /// 16-bit floating-point disparity values.
50 ///
51 /// Depth -> disparity conversion is done with the formula:
52 ///
53 /// disparity = baseline * focal_length / depth
54 ///
55 Disparity16 = sys::rs2_format_RS2_FORMAT_DISPARITY16 as i32,
56 /// 32-bit floating-point disparity values.
57 ///
58 /// Depth -> disparity conversion is done with the formula:
59 ///
60 /// disparity = baseline * focal_length / depth
61 ///
62 Disparity32 = sys::rs2_format_RS2_FORMAT_DISPARITY32 as i32,
63 /// Motion data packed as 3 32-bit fload values in [x, y, z] order
64 MotionXyz32F = sys::rs2_format_RS2_FORMAT_MOTION_XYZ32F as i32,
65 /// 8-bit raw image
66 Raw8 = sys::rs2_format_RS2_FORMAT_RAW8 as i32,
67 /// Four 10-bit per pixel luminance values packed into a 5-byte macropixel
68 Raw10 = sys::rs2_format_RS2_FORMAT_RAW10 as i32,
69 /// 16-bit raw image
70 Raw16 = sys::rs2_format_RS2_FORMAT_RAW16 as i32,
71 /// 8-bit red, green and blue channels (in that order)
72 Rgb8 = sys::rs2_format_RS2_FORMAT_RGB8 as i32,
73 /// 8-bit red, green, blue, and alpha channels (in that order)
74 ///
75 /// alpha channel is always equal to 0xFF
76 Rgba8 = sys::rs2_format_RS2_FORMAT_RGBA8 as i32,
77 /// Grey-scale image as a bit-packed array.
78 ///
79 /// 4 pixel data stream taking 5 bytes.
80 W10 = sys::rs2_format_RS2_FORMAT_W10 as i32,
81 /// 32-bit floating point 3D coordinates in [x, y, z] order
82 Xyz32F = sys::rs2_format_RS2_FORMAT_XYZ32F as i32,
83 /// 8-bit per pixel grayscale image
84 Y8 = sys::rs2_format_RS2_FORMAT_Y8 as i32,
85 /// 8-bit per pixel interleaved.
86 ///
87 /// 8-bit left, 8-bit right.
88 Y8I = sys::rs2_format_RS2_FORMAT_Y8I as i32,
89 /// 16-bit per pixel grayscale image unpacked from 10-bit per pixel packed data.
90 ///
91 /// 10-bit data is packed as (\[8:8:8:8:2222\]).
92 ///
93 /// The data is unpacked to LSB and padded with 6 zero bits.
94 Y10Bpack = sys::rs2_format_RS2_FORMAT_Y10BPACK as i32,
95 /// 12-bits per pixel interleaved.
96 ///
97 /// 12-bit left, 12-bit right.
98 ///
99 /// Each pixel is stored in a 24-bit word in little-endian order.
100 Y12I = sys::rs2_format_RS2_FORMAT_Y12I as i32,
101 /// 16-bit per pixel grayscale image
102 Y16 = sys::rs2_format_RS2_FORMAT_Y16 as i32,
103 /// 16-bit linear depth values
104 ///
105 /// The depth in metres is equal to depth scale multiplied by each pixel value.
106 Z16 = sys::rs2_format_RS2_FORMAT_Z16 as i32,
107 /// Variable-length Huffman-compressed 16-bit depth values
108 Z16H = sys::rs2_format_RS2_FORMAT_Z16H as i32,
109 /// 16-bit per pixel frame grabber format
110 Fg = sys::rs2_format_RS2_FORMAT_FG as i32,
111 /// 12-bit per pixel
112 Y411 = sys::rs2_format_RS2_FORMAT_Y411 as i32,
113 // Not included since this just tells us the total number of formats
114 //
115 // Count = sys::rs2_format_RS2_FORMAT_COUNT,
116}
117
118#[cfg(test)]
119mod tests {
120 use super::*;
121 use num_traits::FromPrimitive;
122
123 #[test]
124 fn all_variants_exist() {
125 for i in 0..sys::rs2_format_RS2_FORMAT_COUNT as i32 {
126 assert!(
127 Rs2Format::from_i32(i).is_some(),
128 "Rs2Format variant for ordinal {} does not exist.",
129 i
130 );
131 }
132 }
133}