From 8526b2565466fcbfab26e19f4234f6b9402cf391 Mon Sep 17 00:00:00 2001 From: Murilo Belluzzo Date: Sun, 2 Oct 2016 23:50:42 -0300 Subject: [PATCH] RingBuffer: Add a faster method to read a single byte --- libraries/AP_HAL/utility/RingBuffer.cpp | 16 ++++++++++++++++ libraries/AP_HAL/utility/RingBuffer.h | 3 +++ 2 files changed, 19 insertions(+) diff --git a/libraries/AP_HAL/utility/RingBuffer.cpp b/libraries/AP_HAL/utility/RingBuffer.cpp index db4735150e..51ad08f97d 100644 --- a/libraries/AP_HAL/utility/RingBuffer.cpp +++ b/libraries/AP_HAL/utility/RingBuffer.cpp @@ -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 */ diff --git a/libraries/AP_HAL/utility/RingBuffer.h b/libraries/AP_HAL/utility/RingBuffer.h index f8d5636de0..6bac86f790 100644 --- a/libraries/AP_HAL/utility/RingBuffer.h +++ b/libraries/AP_HAL/utility/RingBuffer.h @@ -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