mavlink_core/
peek_reader.rs

1//! This module implements a buffered/peekable reader.
2//!
3//! The purpose of the buffered/peekable reader is to allow for backtracking parsers.
4//!
5//! A reader implementing the standard library's [`std::io::BufRead`] trait seems like a good fit, but
6//! it does not allow for peeking a specific number of bytes, so it provides no way to request
7//! more data from the underlying reader without consuming the existing data.
8//!
9//! This API still tries to adhere to the [`std::io::BufRead`]'s trait philosophy.
10//!
11//! The main type `PeekReader`does not implement [`std::io::Read`] itself, as there is no added benefit
12//! in doing so.
13//!
14#[cfg(any(feature = "embedded", feature = "embedded-hal-02"))]
15use crate::embedded::Read;
16
17#[cfg(feature = "std")]
18use std::io::Read;
19
20#[cfg(all(doc, feature = "std"))]
21use std::io::ErrorKind;
22
23use crate::error::MessageReadError;
24
25/// A buffered/peekable reader
26///
27/// This reader wraps a type implementing [`Read`] and adds buffering via an internal buffer.
28///
29/// It allows the user to `peek` a specified number of bytes (without consuming them),
30/// to `read` bytes (consuming them), or to `consume` them after `peek`ing.
31///
32/// NOTE: This reader is generic over the size of the buffer, defaulting to MAVLink's current largest
33/// possible message size of 280 bytes
34///
35pub struct PeekReader<R, const BUFFER_SIZE: usize = 280> {
36    // Internal buffer
37    buffer: [u8; BUFFER_SIZE],
38    // The position of the next byte to read from the buffer.
39    cursor: usize,
40    // The position of the next byte to read into the buffer.
41    top: usize,
42    // The wrapped reader.
43    reader: R,
44}
45
46impl<R: Read, const BUFFER_SIZE: usize> PeekReader<R, BUFFER_SIZE> {
47    /// Instantiates a new [`PeekReader`], wrapping the provided [`Read`]er and using the default chunk size
48    pub fn new(reader: R) -> Self {
49        Self {
50            buffer: [0; BUFFER_SIZE],
51            cursor: 0,
52            top: 0,
53            reader,
54        }
55    }
56
57    /// Peeks an exact amount of bytes from the internal buffer
58    ///
59    /// If the internal buffer does not contain enough data, this function will read
60    /// from the underlying [`Read`]er until it does, an error occurs or no more data can be read (EOF).
61    ///
62    /// This function does not consume data from the buffer, so subsequent calls to `peek` or `read` functions
63    /// will still return the peeked data.
64    ///
65    /// # Errors
66    ///
67    /// - If any error occurs while reading from the underlying [`Read`]er it is returned
68    /// - If an EOF occurs and the specified amount could not be read, this function will return an [`ErrorKind::UnexpectedEof`].
69    ///
70    /// # Panics
71    ///
72    /// Will panic when attempting to read more bytes then `BUFFER_SIZE`
73    pub fn peek_exact(&mut self, amount: usize) -> Result<&[u8], MessageReadError> {
74        let result = self.fetch(amount, false);
75        result
76    }
77
78    /// Reads a specified amount of bytes from the internal buffer
79    ///
80    /// If the internal buffer does not contain enough data, this function will read
81    /// from the underlying [`Read`]er until it does, an error occurs or no more data can be read (EOF).
82    ///
83    /// This function consumes the data from the buffer, unless an error occurs, in which case no data is consumed.
84    ///
85    /// # Errors
86    ///
87    /// - If any error occurs while reading from the underlying [`Read`]er it is returned
88    /// - If an EOF occurs and the specified amount could not be read, this function will return an [`ErrorKind::UnexpectedEof`].
89    ///
90    /// # Panics
91    ///
92    /// Will panic when attempting to read more bytes then `BUFFER_SIZE`
93    pub fn read_exact(&mut self, amount: usize) -> Result<&[u8], MessageReadError> {
94        self.fetch(amount, true)
95    }
96
97    /// Reads a byte from the internal buffer
98    ///
99    /// If the internal buffer does not contain enough data, this function will read
100    /// from the underlying [`Read`]er until it does, an error occurs or no more data can be read (EOF).
101    ///
102    /// This function consumes the data from the buffer, unless an error occurs, in which case no data is consumed.
103    ///
104    /// # Errors
105    ///
106    /// - If any error occurs while reading from the underlying [`Read`]er it is returned
107    /// - If an EOF occurs before a byte could be read, this function will return an [`ErrorKind::UnexpectedEof`].
108    ///
109    /// # Panics
110    ///
111    /// Will panic if this `PeekReader`'s `BUFFER_SIZE` is 0.  
112    pub fn read_u8(&mut self) -> Result<u8, MessageReadError> {
113        let buf = self.read_exact(1)?;
114        Ok(buf[0])
115    }
116
117    /// Consumes a specified amount of bytes from the buffer
118    ///
119    /// If the internal buffer does not contain enough data, this function will consume as much data as is buffered.
120    ///
121    pub fn consume(&mut self, amount: usize) -> usize {
122        let amount = amount.min(self.top - self.cursor);
123        self.cursor += amount;
124        amount
125    }
126
127    /// Returns an immutable reference to the underlying [`Read`]er
128    ///
129    /// Reading directly from the underlying reader will cause data loss
130    pub fn reader_ref(&self) -> &R {
131        &self.reader
132    }
133
134    /// Returns a mutable reference to the underlying [`Read`]er
135    ///
136    /// Reading directly from the underlying reader will cause data loss
137    pub fn reader_mut(&mut self) -> &mut R {
138        &mut self.reader
139    }
140
141    /// Internal function to fetch data from the internal buffer and/or reader
142    fn fetch(&mut self, amount: usize, consume: bool) -> Result<&[u8], MessageReadError> {
143        loop {
144            let buffered = self.top - self.cursor;
145
146            if buffered >= amount {
147                break;
148            }
149
150            // the caller requested more bytes than we have buffered, fetch them from the reader
151            let bytes_to_read = amount - buffered;
152            assert!(bytes_to_read < BUFFER_SIZE);
153
154            // Check if we need to compact the buffer first
155            if self.top + bytes_to_read > BUFFER_SIZE {
156                // Move unread data to the beginning of the buffer
157                self.buffer.copy_within(self.cursor..self.top, 0);
158                self.top = buffered;
159                self.cursor = 0;
160            }
161
162            // Now we can safely read directly into the buffer
163            let end_pos = self.top + bytes_to_read;
164
165            // read needed bytes from reader
166            let bytes_read = self.reader.read(&mut self.buffer[self.top..end_pos])?;
167
168            if bytes_read == 0 {
169                return Err(MessageReadError::eof());
170            }
171
172            self.top += bytes_read;
173        }
174
175        let result = &self.buffer[self.cursor..self.cursor + amount];
176        if consume {
177            self.cursor += amount;
178        }
179        Ok(result)
180    }
181}
182
183#[cfg(test)]
184mod tests {
185    use super::*;
186
187    #[cfg(feature = "std")]
188    use std::io::Write;
189
190    #[cfg(not(feature = "std"))]
191    use embedded_io::Write;
192
193    #[test]
194    fn test_read_and_peek() {
195        let data = b"Hello, World!";
196        let mut buffer = [0u8; 280];
197
198        let mut writer: &mut [u8] = &mut buffer[..];
199        writer.write_all(data).unwrap();
200
201        let mut reader = PeekReader::<_, 280>::new(&buffer[..data.len()]);
202
203        let peeked = reader.peek_exact(5).unwrap();
204        assert_eq!(peeked, b"Hello");
205
206        let read = reader.read_exact(5).unwrap();
207        assert_eq!(read, b"Hello");
208
209        // Make sure `PeekReader::read_exact` consumed the first 5 bytes.
210        let read = reader.read_exact(8).unwrap();
211        assert_eq!(read, b", World!");
212
213        match reader.read_u8().unwrap_err() {
214            #[cfg(feature = "std")]
215            MessageReadError::Io(io_err) => {
216                assert_eq!(io_err.kind(), std::io::ErrorKind::UnexpectedEof);
217            }
218            #[cfg(not(feature = "std"))]
219            MessageReadError::Io => (),
220            _ => panic!("Expected Io error with UnexpectedEof"),
221        }
222    }
223}