From 630a87d9a976446201bf3f101d714e85d2bcd19a Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Mon, 12 May 2014 14:55:37 -0700 Subject: [PATCH] AP_Buffer: remove scalar assignment so that non-scalars can be buffered --- libraries/AP_Buffer/AP_Buffer.h | 18 +++++++----------- 1 file changed, 7 insertions(+), 11 deletions(-) diff --git a/libraries/AP_Buffer/AP_Buffer.h b/libraries/AP_Buffer/AP_Buffer.h index 1cc52cc0ff..f8b8c1149c 100644 --- a/libraries/AP_Buffer/AP_Buffer.h +++ b/libraries/AP_Buffer/AP_Buffer.h @@ -107,14 +107,16 @@ T AP_Buffer::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::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;