AP_HAL: added set_size_best() for ByteBuffer

This commit is contained in:
Andrew Tridgell 2023-07-17 14:38:26 +10:00
parent 1696464bac
commit 8a8a45dd23
2 changed files with 17 additions and 0 deletions

View File

@ -41,6 +41,20 @@ bool ByteBuffer::set_size(uint32_t _size)
return true;
}
/*
set buffer size, accepting a smaller size if desired size isn't achievable
*/
bool ByteBuffer::set_size_best(uint32_t _size)
{
while (_size > 0) {
if (set_size(_size)) {
return true;
}
_size = (3 * _size)/4;
}
return false;
}
uint32_t ByteBuffer::available(void) const
{
/* use a copy on stack to avoid race conditions of @tail being updated by

View File

@ -52,6 +52,9 @@ public:
// set size of ringbuffer, caller responsible for locking
bool set_size(uint32_t size);
// set size of ringbuffer, reducing down if size can't be achieved
bool set_size_best(uint32_t size);
// advance the read pointer (discarding bytes)
bool advance(uint32_t n);