mavlink_core/
bytes.rs

1pub struct Bytes<'a> {
2    data: &'a [u8],
3    pos: usize,
4}
5
6impl<'a> Bytes<'a> {
7    pub fn new(data: &'a [u8]) -> Self {
8        Self { data, pos: 0 }
9    }
10
11    #[inline]
12    fn remaining(&self) -> usize {
13        self.data.len() - self.pos
14    }
15
16    #[inline]
17    pub fn remaining_bytes(&self) -> &'a [u8] {
18        &self.data[self.pos..]
19    }
20
21    #[inline]
22    fn check_remaining(&self, count: usize) {
23        assert!(
24            self.remaining() >= count,
25            "read buffer exhausted; remaining {} bytes, try read {count} bytes",
26            self.remaining(),
27        );
28    }
29
30    /// # Panics
31    ///
32    /// Will panic if not at least `count` bytes remain in the buffer
33    #[inline]
34    pub fn get_bytes(&mut self, count: usize) -> &[u8] {
35        self.check_remaining(count);
36
37        let bytes = &self.data[self.pos..(self.pos + count)];
38        self.pos += count;
39        bytes
40    }
41
42    /// # Panics
43    ///
44    /// Will panic if not at least `SIZE` bytes remain in the buffer
45    #[inline]
46    pub fn get_array<const SIZE: usize>(&mut self) -> [u8; SIZE] {
47        let bytes = self.get_bytes(SIZE);
48        let mut arr = [0u8; SIZE];
49
50        arr.copy_from_slice(bytes);
51
52        debug_assert_eq!(arr.as_slice(), bytes);
53
54        arr
55    }
56
57    /// # Panics
58    ///
59    /// Will panic if nothing is remaining in the buffer
60    #[inline]
61    pub fn get_u8(&mut self) -> u8 {
62        self.check_remaining(1);
63
64        let val = self.data[self.pos];
65        self.pos += 1;
66        val
67    }
68
69    /// # Panics
70    ///
71    /// Will panic if nothing is remaining in the buffer
72    #[inline]
73    pub fn get_i8(&mut self) -> i8 {
74        self.check_remaining(1);
75
76        let val = self.data[self.pos] as i8;
77        self.pos += 1;
78        val
79    }
80
81    /// # Panics
82    ///
83    /// Will panic if less then the 2 required bytes for a `u16` remain
84    #[inline]
85    pub fn get_u16_le(&mut self) -> u16 {
86        u16::from_le_bytes(self.get_array())
87    }
88
89    /// # Panics
90    ///
91    /// Will panic if less then the 2 required bytes for a `i16` remain
92    #[inline]
93    pub fn get_i16_le(&mut self) -> i16 {
94        i16::from_le_bytes(self.get_array())
95    }
96
97    /// # Panics
98    ///
99    /// Will panic if not at least 3 bytes remain
100    #[inline]
101    pub fn get_u24_le(&mut self) -> u32 {
102        const SIZE: usize = 3;
103        self.check_remaining(SIZE);
104
105        let mut val = [0u8; SIZE + 1];
106        val[..3].copy_from_slice(&self.data[self.pos..self.pos + SIZE]);
107        self.pos += SIZE;
108
109        debug_assert_eq!(val[3], 0);
110        u32::from_le_bytes(val)
111    }
112
113    /// # Panics
114    ///
115    /// Will panic if not at least 3 bytes remain
116    #[inline]
117    pub fn get_i24_le(&mut self) -> i32 {
118        const SIZE: usize = 3;
119        self.check_remaining(SIZE);
120
121        let mut val = [0u8; SIZE + 1];
122        val[..3].copy_from_slice(&self.data[self.pos..self.pos + SIZE]);
123        self.pos += SIZE;
124
125        debug_assert_eq!(val[3], 0);
126        i32::from_le_bytes(val)
127    }
128
129    /// # Panics
130    ///
131    /// Will panic if less then the 4 required bytes for a `u32` remain
132    #[inline]
133    pub fn get_u32_le(&mut self) -> u32 {
134        u32::from_le_bytes(self.get_array())
135    }
136
137    /// # Panics
138    ///
139    /// Will panic if less then the 4 required bytes for a `i32` remain
140    #[inline]
141    pub fn get_i32_le(&mut self) -> i32 {
142        i32::from_le_bytes(self.get_array())
143    }
144
145    /// # Panics
146    ///
147    /// Will panic if less then the 8 required bytes for a `u64` remain
148    #[inline]
149    pub fn get_u64_le(&mut self) -> u64 {
150        u64::from_le_bytes(self.get_array())
151    }
152
153    /// # Panics
154    ///
155    /// Will panic if less then the 8 required bytes for a `i64` remain
156    #[inline]
157    pub fn get_i64_le(&mut self) -> i64 {
158        i64::from_le_bytes(self.get_array())
159    }
160
161    /// # Panics
162    ///
163    /// Will panic if less then the 4 required bytes for a `f32` remain
164    #[inline]
165    pub fn get_f32_le(&mut self) -> f32 {
166        f32::from_le_bytes(self.get_array())
167    }
168
169    /// # Panics
170    ///
171    /// Will panic if less then the 8 required bytes for a `f64` remain
172    #[inline]
173    pub fn get_f64_le(&mut self) -> f64 {
174        f64::from_le_bytes(self.get_array())
175    }
176}