mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
RingBuffer: Add a faster method to read a single byte
This commit is contained in:
parent
4e86ef9b47
commit
8526b25654
@ -196,6 +196,22 @@ uint32_t ByteBuffer::read(uint8_t *data, uint32_t len)
|
||||
return ret;
|
||||
}
|
||||
|
||||
bool ByteBuffer::read_byte(uint8_t *data)
|
||||
{
|
||||
if (!data) {
|
||||
return false;
|
||||
}
|
||||
|
||||
int16_t ret = peek(0);
|
||||
if (ret < 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
*data = ret;
|
||||
|
||||
return advance(1);
|
||||
}
|
||||
|
||||
/*
|
||||
* Returns the pointer and size to a contiguous read in the buffer
|
||||
*/
|
||||
|
@ -50,6 +50,9 @@ public:
|
||||
// read bytes from ringbuffer. Returns number of bytes read
|
||||
uint32_t read(uint8_t *data, uint32_t len);
|
||||
|
||||
// read a byte from ring buffer. Returns true on success, false otherwise
|
||||
bool read_byte(uint8_t *data);
|
||||
|
||||
/*
|
||||
update bytes at the read pointer. Used to update an object without
|
||||
popping it
|
||||
|
Loading…
Reference in New Issue
Block a user