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    #[inline]
31    pub fn get_bytes(&mut self, count: usize) -> &[u8] {
32        self.check_remaining(count);
33
34        let bytes = &self.data[self.pos..(self.pos + count)];
35        self.pos += count;
36        bytes
37    }
38
39    #[inline]
40    pub fn get_array<const SIZE: usize>(&mut self) -> [u8; SIZE] {
41        let bytes = self.get_bytes(SIZE);
42        let mut arr = [0u8; SIZE];
43
44        arr.copy_from_slice(bytes);
45
46        debug_assert_eq!(arr.as_slice(), bytes);
47
48        arr
49    }
50
51    #[inline]
52    pub fn get_u8(&mut self) -> u8 {
53        self.check_remaining(1);
54
55        let val = self.data[self.pos];
56        self.pos += 1;
57        val
58    }
59
60    #[inline]
61    pub fn get_i8(&mut self) -> i8 {
62        self.check_remaining(1);
63
64        let val = self.data[self.pos] as i8;
65        self.pos += 1;
66        val
67    }
68
69    #[inline]
70    pub fn get_u16_le(&mut self) -> u16 {
71        u16::from_le_bytes(self.get_array())
72    }
73
74    #[inline]
75    pub fn get_i16_le(&mut self) -> i16 {
76        i16::from_le_bytes(self.get_array())
77    }
78
79    #[inline]
80    pub fn get_u24_le(&mut self) -> u32 {
81        const SIZE: usize = 3;
82        self.check_remaining(SIZE);
83
84        let mut val = [0u8; SIZE + 1];
85        val[..3].copy_from_slice(&self.data[self.pos..self.pos + SIZE]);
86        self.pos += SIZE;
87
88        debug_assert_eq!(val[3], 0);
89        u32::from_le_bytes(val)
90    }
91
92    #[inline]
93    pub fn get_i24_le(&mut self) -> i32 {
94        const SIZE: usize = 3;
95        self.check_remaining(SIZE);
96
97        let mut val = [0u8; SIZE + 1];
98        val[..3].copy_from_slice(&self.data[self.pos..self.pos + SIZE]);
99        self.pos += SIZE;
100
101        debug_assert_eq!(val[3], 0);
102        i32::from_le_bytes(val)
103    }
104
105    #[inline]
106    pub fn get_u32_le(&mut self) -> u32 {
107        u32::from_le_bytes(self.get_array())
108    }
109
110    #[inline]
111    pub fn get_i32_le(&mut self) -> i32 {
112        i32::from_le_bytes(self.get_array())
113    }
114
115    #[inline]
116    pub fn get_u64_le(&mut self) -> u64 {
117        u64::from_le_bytes(self.get_array())
118    }
119
120    #[inline]
121    pub fn get_i64_le(&mut self) -> i64 {
122        i64::from_le_bytes(self.get_array())
123    }
124
125    #[inline]
126    pub fn get_f32_le(&mut self) -> f32 {
127        f32::from_le_bytes(self.get_array())
128    }
129
130    #[inline]
131    pub fn get_f64_le(&mut self) -> f64 {
132        f64::from_le_bytes(self.get_array())
133    }
134}