Browse Source

RingBuffer: ::set_size now returns true or false

mission-4.1.18
Murilo Belluzzo 9 years ago committed by Lucas De Marchi
parent
commit
b856d26087
  1. 16
      libraries/AP_HAL/utility/RingBuffer.cpp
  2. 2
      libraries/AP_HAL/utility/RingBuffer.h

16
libraries/AP_HAL/utility/RingBuffer.cpp

@ -17,17 +17,21 @@ ByteBuffer::~ByteBuffer(void) @@ -17,17 +17,21 @@ ByteBuffer::~ByteBuffer(void)
/*
* Caller is responsible for locking in set_size()
*/
void ByteBuffer::set_size(uint32_t _size)
bool ByteBuffer::set_size(uint32_t _size)
{
uint8_t *oldbuf;
head = tail = 0;
if (_size != size) {
oldbuf = buf;
free(buf);
buf = (uint8_t*)malloc(_size);
size = buf ? _size : 0;
free(oldbuf);
if (!buf) {
size = 0;
return false;
}
size = _size;
}
return true;
}
uint32_t ByteBuffer::available(void) const

2
libraries/AP_HAL/utility/RingBuffer.h

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

Loading…
Cancel
Save