mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Buffer: remove scalar assignment so that non-scalars can be buffered
This commit is contained in:
parent
834c91b192
commit
630a87d9a9
@ -107,14 +107,16 @@ T AP_Buffer<T,SIZE>::pop_front()
|
||||
{
|
||||
T result;
|
||||
|
||||
// return zero if buffer is empty
|
||||
if( _num_items == 0 ) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// get next value in buffer
|
||||
result = _buff[_head];
|
||||
|
||||
if(_num_items == 0) {
|
||||
// return whatever is at _head
|
||||
// don't return zero because it is a scalar value
|
||||
// don't return T() because PX4 compiler does not support it
|
||||
return result;
|
||||
}
|
||||
|
||||
// increment to next point
|
||||
_head++;
|
||||
if( _head >= SIZE )
|
||||
@ -132,12 +134,6 @@ const T& AP_Buffer<T,SIZE>::peek(uint8_t position) const
|
||||
{
|
||||
uint8_t j = _head + position;
|
||||
|
||||
// return zero if position is out of range
|
||||
if( position >= _num_items ) {
|
||||
const static T r = 0;
|
||||
return r;
|
||||
}
|
||||
|
||||
// wrap around if necessary
|
||||
if( j >= SIZE )
|
||||
j -= SIZE;
|
||||
|
Loading…
Reference in New Issue
Block a user