Browse Source

AP_HAL: Simplify ByteBuffer::readptr logic

master
Murilo Belluzzo 9 years ago committed by Lucas De Marchi
parent
commit
e9e31172c0
  1. 14
      libraries/AP_HAL/utility/RingBuffer.cpp
  2. 2
      libraries/AP_HAL/utility/RingBuffer.h

14
libraries/AP_HAL/utility/RingBuffer.cpp

@ -176,18 +176,14 @@ uint32_t ByteBuffer::read(uint8_t *data, uint32_t len) @@ -176,18 +176,14 @@ uint32_t ByteBuffer::read(uint8_t *data, uint32_t len)
}
/*
return a pointer to a contiguous read buffer
* Returns the pointer and size to a contiguous read in the buffer
*/
const uint8_t *ByteBuffer::readptr(uint32_t &available_bytes)
{
available_bytes = available();
if (available_bytes == 0) {
return nullptr;
}
if (head+available_bytes > size) {
available_bytes = size - head;
}
return &buf[head];
uint32_t _tail = tail;
available_bytes = (head > _tail) ? size - head : _tail - head;
return available_bytes ? &buf[head] : nullptr;
}
int16_t ByteBuffer::peek(uint32_t ofs) const

2
libraries/AP_HAL/utility/RingBuffer.h

@ -61,7 +61,7 @@ public: @@ -61,7 +61,7 @@ public:
// advance the read pointer (discarding bytes)
bool advance(uint32_t n);
// return a pointer to the next available data
// Returns the pointer and size to a contiguous read of the next available data
const uint8_t *readptr(uint32_t &available_bytes);
// peek one byte without advancing read pointer. Return byte

Loading…
Cancel
Save