diff --git a/libraries/AP_HAL/utility/RingBuffer.cpp b/libraries/AP_HAL/utility/RingBuffer.cpp index 5d232db066..a5e83ec896 100644 --- a/libraries/AP_HAL/utility/RingBuffer.cpp +++ b/libraries/AP_HAL/utility/RingBuffer.cpp @@ -1,4 +1,5 @@ #include "RingBuffer.h" +#include #include #include @@ -109,10 +110,7 @@ bool ByteBuffer::advance(uint32_t n) return true; } -/* - read len bytes without advancing the read pointer - */ -uint32_t ByteBuffer::peekbytes(uint8_t *data, uint32_t len) +int ByteBuffer::peekiovec(ByteBuffer::IoVec iovec[2], uint32_t len) { if (len > available()) { len = available(); @@ -121,22 +119,42 @@ uint32_t ByteBuffer::peekbytes(uint8_t *data, uint32_t len) return 0; } uint32_t n; - const uint8_t *b = readptr(n); + auto b = readptr(n); if (n > len) { n = len; } - // perform first memcpy - memcpy(data, b, n); - data += n; + iovec[0].data = const_cast(b); + iovec[0].len = n; if (len > n) { - // possible second memcpy, must be from front of buffer - memcpy(data, buf, len-n); + iovec[1].data = buf; + iovec[1].len = len - n; + + return 2; } - return len; + + return 1; } +/* + read len bytes without advancing the read pointer + */ +uint32_t ByteBuffer::peekbytes(uint8_t *data, uint32_t len) +{ + ByteBuffer::IoVec vec[2]; + const auto n_vec = peekiovec(vec, len); + uint32_t ret = 0; + + for (int i = 0; i < n_vec; i++) { + memcpy(data + ret, vec[i].data, vec[i].len); + ret += vec[i].len; + } + + return ret; +} + + uint32_t ByteBuffer::read(uint8_t *data, uint32_t len) { uint32_t ret = peekbytes(data, len); diff --git a/libraries/AP_HAL/utility/RingBuffer.h b/libraries/AP_HAL/utility/RingBuffer.h index 68c53bbefa..40bb2f5b72 100644 --- a/libraries/AP_HAL/utility/RingBuffer.h +++ b/libraries/AP_HAL/utility/RingBuffer.h @@ -72,6 +72,15 @@ public: read len bytes without advancing the read pointer */ uint32_t peekbytes(uint8_t *data, uint32_t len); + + // Similar to peekbytes(), but will fill out IoVec struct with + // both parts of the ring buffer if wraparound is happpening, or + // just one part. Returns the number of parts written to. + struct IoVec { + uint8_t *data; + uint32_t len; + }; + int peekiovec(IoVec vec[2], uint32_t len); private: uint8_t *buf = nullptr;