mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: rename ringbuffer empty() to is_empty()
This commit is contained in:
parent
f59d2fdbf4
commit
fd3dd77489
|
@ -71,7 +71,7 @@ uint32_t ByteBuffer::space(void) const
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool ByteBuffer::empty(void) const
|
bool ByteBuffer::is_empty(void) const
|
||||||
{
|
{
|
||||||
return head == tail;
|
return head == tail;
|
||||||
}
|
}
|
||||||
|
|
|
@ -24,7 +24,7 @@ public:
|
||||||
uint32_t space(void) const;
|
uint32_t space(void) const;
|
||||||
|
|
||||||
// true if available() is zero
|
// true if available() is zero
|
||||||
bool empty(void) const;
|
bool is_empty(void) const;
|
||||||
|
|
||||||
// write bytes to ringbuffer. Returns number of bytes written
|
// write bytes to ringbuffer. Returns number of bytes written
|
||||||
uint32_t write(const uint8_t *data, uint32_t len);
|
uint32_t write(const uint8_t *data, uint32_t len);
|
||||||
|
@ -142,8 +142,8 @@ public:
|
||||||
|
|
||||||
// true is available() == 0
|
// true is available() == 0
|
||||||
// !!! Note ObjectBuffer_TS is a duplicate of this update, in both places !!!
|
// !!! Note ObjectBuffer_TS is a duplicate of this update, in both places !!!
|
||||||
bool empty(void) const {
|
bool is_empty(void) const {
|
||||||
return buffer->empty();
|
return buffer->is_empty();
|
||||||
}
|
}
|
||||||
|
|
||||||
// push one object onto the back of the queue
|
// push one object onto the back of the queue
|
||||||
|
@ -309,9 +309,9 @@ public:
|
||||||
|
|
||||||
// true is available() == 0
|
// true is available() == 0
|
||||||
// !!! Note this is a duplicate of ObjectBuffer with semaphore, update in both places !!!
|
// !!! Note this is a duplicate of ObjectBuffer with semaphore, update in both places !!!
|
||||||
bool empty(void) {
|
bool is_empty(void) {
|
||||||
WITH_SEMAPHORE(sem);
|
WITH_SEMAPHORE(sem);
|
||||||
return buffer->empty();
|
return buffer->is_empty();
|
||||||
}
|
}
|
||||||
|
|
||||||
// push one object onto the back of the queue
|
// push one object onto the back of the queue
|
||||||
|
@ -459,7 +459,7 @@ public:
|
||||||
}
|
}
|
||||||
|
|
||||||
// true is available() == 0
|
// true is available() == 0
|
||||||
bool empty(void) const {
|
bool is_empty(void) const {
|
||||||
return _count == 0;
|
return _count == 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -477,7 +477,7 @@ public:
|
||||||
throw away an object
|
throw away an object
|
||||||
*/
|
*/
|
||||||
bool pop(void) {
|
bool pop(void) {
|
||||||
if (empty()) {
|
if (is_empty()) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
_head = (_head+1) % _size;
|
_head = (_head+1) % _size;
|
||||||
|
@ -495,7 +495,7 @@ public:
|
||||||
pop earliest object off the queue
|
pop earliest object off the queue
|
||||||
*/
|
*/
|
||||||
bool pop(T &object) {
|
bool pop(T &object) {
|
||||||
if (empty()) {
|
if (is_empty()) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
object = _buffer[_head];
|
object = _buffer[_head];
|
||||||
|
|
Loading…
Reference in New Issue