mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
RingBuffer: Add ::clear() method to discard the buffer content
The same could be achieved with ::set_size(::get_size()), but was not obvious and hurts code readability.
This commit is contained in:
parent
75a1b102fb
commit
f7f203efa9
@ -36,6 +36,11 @@ uint32_t ByteBuffer::available(void) const
|
||||
return ((head > (_tail=tail))? (size - head) + _tail: _tail - head);
|
||||
}
|
||||
|
||||
void ByteBuffer::clear(void)
|
||||
{
|
||||
head = tail = 0;
|
||||
}
|
||||
|
||||
uint32_t ByteBuffer::space(void) const
|
||||
{
|
||||
uint32_t _head = head;
|
||||
|
@ -35,6 +35,9 @@ public:
|
||||
// number of bytes available to be read
|
||||
uint32_t available(void) const;
|
||||
|
||||
// Discards the buffer content, emptying it.
|
||||
void clear(void);
|
||||
|
||||
// number of bytes space available to write
|
||||
uint32_t space(void) const;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user