Browse Source

AP_HAL: Improve ByteBuffer::set_size

So it doesn't delete and re-create the buffer if the size
happens to be the same. Still resets the buffer content.
mission-4.1.18
Murilo Belluzzo 9 years ago committed by Lucas De Marchi
parent
commit
625f47def7
  1. 8
      libraries/AP_HAL/utility/RingBuffer.cpp

8
libraries/AP_HAL/utility/RingBuffer.cpp

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

Loading…
Cancel
Save