Browse Source

AP_HAL: added set_size() to RingBuffer API

master
Andrew Tridgell 9 years ago
parent
commit
595d5c0002
  1. 12
      libraries/AP_HAL/utility/RingBuffer.cpp
  2. 3
      libraries/AP_HAL/utility/RingBuffer.h

12
libraries/AP_HAL/utility/RingBuffer.cpp

@ -18,6 +18,18 @@ ByteBuffer::~ByteBuffer(void) @@ -18,6 +18,18 @@ ByteBuffer::~ByteBuffer(void)
delete [] buf;
}
/*
caller is responsible for locking in set_size()
*/
void ByteBuffer::set_size(uint32_t _size)
{
uint8_t *oldbuf = buf;
head = tail = 0;
size = _size;
buf = new uint8_t[size];
delete [] oldbuf;
}
uint32_t ByteBuffer::available(void) const
{
uint32_t _tail;

3
libraries/AP_HAL/utility/RingBuffer.h

@ -55,6 +55,9 @@ public: @@ -55,6 +55,9 @@ public:
// return size of ringbuffer
uint32_t get_size(void) const { return size; }
// set size of ringbuffer, caller responsible for locking
void set_size(uint32_t size);
// advance the read pointer (discarding bytes)
bool advance(uint32_t n);

Loading…
Cancel
Save