mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_Buffer: change pop_front to return a bool if successful
This commit is contained in:
parent
ceef10cc41
commit
1c75ce88f2
@ -26,10 +26,11 @@ public:
|
|||||||
/// @param item
|
/// @param item
|
||||||
void push_back( const T &item );
|
void push_back( const T &item );
|
||||||
|
|
||||||
/// pop_front - removes an element from the begin of the buffer (i.e. the oldest element)
|
/// pop_front - removes an element from the beginning of the
|
||||||
/// and returns it. If the buffer is empty, 0 is returned
|
/// buffer (i.e. the oldest element) and returns it in ret.
|
||||||
/// @return
|
/// @param ret : the removed element, if exists
|
||||||
T pop_front();
|
/// @return : true if successful, false if not
|
||||||
|
bool pop_front(T &ret);
|
||||||
|
|
||||||
/// peek - returns a reference to an element of the buffer
|
/// peek - returns a reference to an element of the buffer
|
||||||
/// if position isn't valid (i.e. >= size()) 0 is returned
|
/// if position isn't valid (i.e. >= size()) 0 is returned
|
||||||
@ -105,20 +106,16 @@ void AP_Buffer<T,SIZE>::push_back( const T &item )
|
|||||||
}
|
}
|
||||||
|
|
||||||
template <class T, uint8_t SIZE>
|
template <class T, uint8_t SIZE>
|
||||||
T AP_Buffer<T,SIZE>::pop_front()
|
bool AP_Buffer<T,SIZE>::pop_front(T &ret)
|
||||||
{
|
{
|
||||||
T result;
|
|
||||||
|
|
||||||
// get next value in buffer
|
|
||||||
result = _buff[_head];
|
|
||||||
|
|
||||||
if(_num_items == 0) {
|
if(_num_items == 0) {
|
||||||
// return whatever is at _head
|
// buffer is empty
|
||||||
// don't return zero because it is a scalar value
|
return false;
|
||||||
// don't return T() because PX4 compiler does not support it
|
|
||||||
return result;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// get next value in buffer
|
||||||
|
ret = _buff[_head];
|
||||||
|
|
||||||
// increment to next point
|
// increment to next point
|
||||||
_head++;
|
_head++;
|
||||||
if( _head >= SIZE )
|
if( _head >= SIZE )
|
||||||
@ -127,8 +124,8 @@ T AP_Buffer<T,SIZE>::pop_front()
|
|||||||
// reduce number of items
|
// reduce number of items
|
||||||
_num_items--;
|
_num_items--;
|
||||||
|
|
||||||
// return item
|
// success
|
||||||
return result;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <class T, uint8_t SIZE>
|
template <class T, uint8_t SIZE>
|
||||||
|
Loading…
Reference in New Issue
Block a user