mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_Buffer: remove bool return from add() method
This commit is contained in:
parent
26fa5c40f1
commit
dcc3873056
@ -25,7 +25,7 @@ void AP_Buffer<T,SIZE>::clear() {
|
|||||||
|
|
||||||
// add - adds an item to the buffer. returns TRUE if successfully added
|
// add - adds an item to the buffer. returns TRUE if successfully added
|
||||||
template <class T, uint8_t SIZE>
|
template <class T, uint8_t SIZE>
|
||||||
bool AP_Buffer<T,SIZE>::add( T item )
|
void AP_Buffer<T,SIZE>::add( T item )
|
||||||
{
|
{
|
||||||
// determine position of new item
|
// determine position of new item
|
||||||
uint8_t tail = _head + _num_items;
|
uint8_t tail = _head + _num_items;
|
||||||
@ -46,9 +46,6 @@ bool AP_Buffer<T,SIZE>::add( T item )
|
|||||||
_head = 0;
|
_head = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// indicate success
|
|
||||||
return true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// get - returns the next value in the buffer
|
// get - returns the next value in the buffer
|
||||||
@ -99,9 +96,9 @@ T AP_Buffer<T,SIZE>::peek(uint8_t position) const
|
|||||||
template float AP_Buffer<float,5>::peek(uint8_t position) const;
|
template float AP_Buffer<float,5>::peek(uint8_t position) const;
|
||||||
template AP_Buffer<float, 5>::AP_Buffer();
|
template AP_Buffer<float, 5>::AP_Buffer();
|
||||||
template void AP_Buffer<float, 5>::clear();
|
template void AP_Buffer<float, 5>::clear();
|
||||||
template bool AP_Buffer<float, 5>::add(float);
|
template void AP_Buffer<float, 5>::add(float);
|
||||||
|
|
||||||
template float AP_Buffer<float,15>::peek(uint8_t position) const;
|
template float AP_Buffer<float,15>::peek(uint8_t position) const;
|
||||||
template AP_Buffer<float, 15>::AP_Buffer();
|
template AP_Buffer<float, 15>::AP_Buffer();
|
||||||
template void AP_Buffer<float, 15>::clear();
|
template void AP_Buffer<float, 15>::clear();
|
||||||
template bool AP_Buffer<float, 15>::add(float);
|
template void AP_Buffer<float, 15>::add(float);
|
||||||
|
@ -19,7 +19,7 @@ public:
|
|||||||
void clear();
|
void clear();
|
||||||
|
|
||||||
// add - adds an item to the buffer. returns TRUE if successfully added
|
// add - adds an item to the buffer. returns TRUE if successfully added
|
||||||
bool add( T item );
|
void add( T item );
|
||||||
|
|
||||||
// get - returns the next value in the buffer
|
// get - returns the next value in the buffer
|
||||||
T get();
|
T get();
|
||||||
|
Loading…
Reference in New Issue
Block a user