RingBuffer: Add a faster method to read a single byte

This commit is contained in:
Murilo Belluzzo 2016-10-02 23:50:42 -03:00 committed by Andrew Tridgell
parent 4e86ef9b47
commit 8526b25654
2 changed files with 19 additions and 0 deletions

View File

@ -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
*/

View File

@ -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