2015-12-19 04:12:40 -04:00
|
|
|
#pragma once
|
|
|
|
|
2016-07-01 16:53:14 -03:00
|
|
|
#include <atomic>
|
2016-07-27 22:03:05 -03:00
|
|
|
#include <stdint.h>
|
2020-03-05 10:59:25 -04:00
|
|
|
#include <AP_HAL/AP_HAL_Boards.h>
|
|
|
|
#include <AP_HAL/AP_HAL_Macros.h>
|
|
|
|
#include <AP_HAL/Semaphores.h>
|
2015-12-19 04:12:40 -04:00
|
|
|
|
|
|
|
/*
|
2016-07-27 22:03:05 -03:00
|
|
|
* Circular buffer of bytes.
|
2015-12-19 04:12:40 -04:00
|
|
|
*/
|
|
|
|
class ByteBuffer {
|
|
|
|
public:
|
|
|
|
ByteBuffer(uint32_t size);
|
2020-07-31 10:37:52 -03:00
|
|
|
ByteBuffer(uint8_t* _buf, uint32_t _size) :
|
|
|
|
buf(_buf),
|
|
|
|
size(_size),
|
|
|
|
external_buf(true)
|
|
|
|
{}
|
2015-12-19 04:12:40 -04:00
|
|
|
~ByteBuffer(void);
|
2016-02-21 21:11:19 -04:00
|
|
|
|
|
|
|
// number of bytes available to be read
|
2015-12-19 04:12:40 -04:00
|
|
|
uint32_t available(void) const;
|
2016-02-21 21:11:19 -04:00
|
|
|
|
2016-07-29 18:05:52 -03:00
|
|
|
// Discards the buffer content, emptying it.
|
|
|
|
void clear(void);
|
|
|
|
|
2016-02-21 21:11:19 -04:00
|
|
|
// number of bytes space available to write
|
2015-12-19 04:12:40 -04:00
|
|
|
uint32_t space(void) const;
|
2016-02-21 21:11:19 -04:00
|
|
|
|
|
|
|
// true if available() is zero
|
2020-06-03 02:27:49 -03:00
|
|
|
bool is_empty(void) const WARN_IF_UNUSED;
|
2016-02-21 21:11:19 -04:00
|
|
|
|
|
|
|
// write bytes to ringbuffer. Returns number of bytes written
|
2015-12-19 04:12:40 -04:00
|
|
|
uint32_t write(const uint8_t *data, uint32_t len);
|
2016-02-21 21:11:19 -04:00
|
|
|
|
|
|
|
// read bytes from ringbuffer. Returns number of bytes read
|
2015-12-19 04:12:40 -04:00
|
|
|
uint32_t read(uint8_t *data, uint32_t len);
|
2016-02-21 21:11:19 -04:00
|
|
|
|
2016-10-02 23:50:42 -03:00
|
|
|
// read a byte from ring buffer. Returns true on success, false otherwise
|
2020-06-03 02:27:49 -03:00
|
|
|
bool read_byte(uint8_t *data) WARN_IF_UNUSED;
|
2016-10-02 23:50:42 -03:00
|
|
|
|
2016-02-22 03:32:51 -04:00
|
|
|
/*
|
|
|
|
update bytes at the read pointer. Used to update an object without
|
|
|
|
popping it
|
|
|
|
*/
|
|
|
|
bool update(const uint8_t *data, uint32_t len);
|
2016-07-08 16:11:04 -03:00
|
|
|
|
2016-02-21 21:11:19 -04:00
|
|
|
// return size of ringbuffer
|
2015-12-19 04:12:40 -04:00
|
|
|
uint32_t get_size(void) const { return size; }
|
2016-02-21 21:11:19 -04:00
|
|
|
|
2016-05-23 10:30:56 -03:00
|
|
|
// set size of ringbuffer, caller responsible for locking
|
2016-08-01 22:48:35 -03:00
|
|
|
bool set_size(uint32_t size);
|
2016-07-08 16:11:04 -03:00
|
|
|
|
2023-07-17 01:38:26 -03:00
|
|
|
// set size of ringbuffer, reducing down if size can't be achieved
|
|
|
|
bool set_size_best(uint32_t size);
|
|
|
|
|
2016-02-21 21:11:19 -04:00
|
|
|
// advance the read pointer (discarding bytes)
|
2015-12-19 04:12:40 -04:00
|
|
|
bool advance(uint32_t n);
|
2016-02-21 21:11:19 -04:00
|
|
|
|
2016-06-23 18:40:44 -03:00
|
|
|
// Returns the pointer and size to a contiguous read of the next available data
|
2015-12-19 04:12:40 -04:00
|
|
|
const uint8_t *readptr(uint32_t &available_bytes);
|
2016-02-21 21:11:19 -04:00
|
|
|
|
|
|
|
// peek one byte without advancing read pointer. Return byte
|
|
|
|
// or -1 if none available
|
2015-12-19 04:12:40 -04:00
|
|
|
int16_t peek(uint32_t ofs) const;
|
2016-02-21 21:11:19 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
read len bytes without advancing the read pointer
|
|
|
|
*/
|
|
|
|
uint32_t peekbytes(uint8_t *data, uint32_t len);
|
2016-05-24 11:00:12 -03:00
|
|
|
|
|
|
|
// Similar to peekbytes(), but will fill out IoVec struct with
|
2016-06-25 22:10:04 -03:00
|
|
|
// both parts of the ring buffer if wraparound is happening, or
|
2016-05-24 11:00:12 -03:00
|
|
|
// just one part. Returns the number of parts written to.
|
|
|
|
struct IoVec {
|
|
|
|
uint8_t *data;
|
|
|
|
uint32_t len;
|
|
|
|
};
|
2016-06-25 22:10:04 -03:00
|
|
|
uint8_t peekiovec(IoVec vec[2], uint32_t len);
|
2016-05-19 19:19:58 -03:00
|
|
|
|
|
|
|
// Reserve `len` bytes and fills out `vec` with both parts of the
|
|
|
|
// ring buffer (if wraparound is happening), or just one contiguous
|
|
|
|
// part. Returns the number of `vec` elements filled out. Can be used
|
|
|
|
// with system calls such as `readv()`.
|
2016-06-23 18:47:24 -03:00
|
|
|
//
|
|
|
|
// After a call to 'reserve()', 'write()' should never be called
|
|
|
|
// until 'commit()' is called!
|
|
|
|
uint8_t reserve(IoVec vec[2], uint32_t len);
|
|
|
|
|
|
|
|
/*
|
|
|
|
* "Releases" the memory previously reserved by 'reserve()' to be read.
|
|
|
|
* Committer must inform how many bytes were actually written in 'len'.
|
|
|
|
*/
|
|
|
|
bool commit(uint32_t len);
|
|
|
|
|
2015-12-19 04:12:40 -04:00
|
|
|
private:
|
2016-07-08 16:08:46 -03:00
|
|
|
uint8_t *buf;
|
|
|
|
uint32_t size;
|
2015-12-19 04:12:40 -04:00
|
|
|
|
2016-07-27 22:03:05 -03:00
|
|
|
std::atomic<uint32_t> head{0}; // where to read data
|
|
|
|
std::atomic<uint32_t> tail{0}; // where to write data
|
2020-07-31 10:37:52 -03:00
|
|
|
|
|
|
|
bool external_buf;
|
2015-12-19 04:12:40 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
/*
|
|
|
|
ring buffer class for objects of fixed size
|
2020-02-02 12:13:12 -04:00
|
|
|
!!! Note ObjectBuffer_TS is a duplicate of this update, in both places !!!
|
2015-12-19 04:12:40 -04:00
|
|
|
*/
|
|
|
|
template <class T>
|
|
|
|
class ObjectBuffer {
|
|
|
|
public:
|
2020-03-05 10:59:25 -04:00
|
|
|
ObjectBuffer(uint32_t _size = 0) {
|
2018-11-03 02:44:15 -03:00
|
|
|
// we set size to 1 more than requested as the byte buffer
|
|
|
|
// gives one less byte than requested. We round up to a full
|
|
|
|
// multiple of the object size so that we always get aligned
|
|
|
|
// elements, which makes the readptr() method possible
|
|
|
|
buffer = new ByteBuffer(((_size+1) * sizeof(T)));
|
2020-07-31 10:37:52 -03:00
|
|
|
external_buf = false;
|
2015-12-19 04:12:40 -04:00
|
|
|
}
|
2020-07-31 10:37:52 -03:00
|
|
|
|
|
|
|
ObjectBuffer(ByteBuffer *_buffer) :
|
|
|
|
buffer(_buffer),
|
|
|
|
external_buf(true)
|
|
|
|
{}
|
|
|
|
|
2015-12-19 04:12:40 -04:00
|
|
|
~ObjectBuffer(void) {
|
2020-07-31 10:37:52 -03:00
|
|
|
if (!external_buf)
|
|
|
|
delete buffer;
|
2015-12-19 04:12:40 -04:00
|
|
|
}
|
|
|
|
|
2020-03-05 10:59:25 -04:00
|
|
|
// return size of ringbuffer
|
2021-01-14 18:57:06 -04:00
|
|
|
uint32_t get_size(void) const {
|
2023-01-01 17:54:16 -04:00
|
|
|
if (buffer == nullptr) {
|
|
|
|
return 0;
|
|
|
|
}
|
2021-01-14 18:57:06 -04:00
|
|
|
uint32_t size = buffer->get_size() / sizeof(T);
|
|
|
|
return size>0?size-1:0;
|
|
|
|
}
|
2020-03-05 10:59:25 -04:00
|
|
|
|
|
|
|
// set size of ringbuffer, caller responsible for locking
|
|
|
|
bool set_size(uint32_t size) { return buffer->set_size(((size+1) * sizeof(T))); }
|
|
|
|
|
|
|
|
// read len objects without advancing the read pointer
|
|
|
|
uint32_t peek(T *data, uint32_t len) { return buffer->peekbytes((uint8_t*)data, len * sizeof(T)) / sizeof(T); }
|
|
|
|
|
2017-04-02 11:54:46 -03:00
|
|
|
// Discards the buffer content, emptying it.
|
2020-02-02 12:13:12 -04:00
|
|
|
// !!! Note ObjectBuffer_TS is a duplicate of this update, in both places !!!
|
2017-04-02 11:54:46 -03:00
|
|
|
void clear(void)
|
|
|
|
{
|
|
|
|
buffer->clear();
|
|
|
|
}
|
|
|
|
|
2019-12-06 05:23:54 -04:00
|
|
|
// return number of objects available to be read from the front of the queue
|
2020-02-02 12:13:12 -04:00
|
|
|
// !!! Note ObjectBuffer_TS is a duplicate of this update, in both places !!!
|
2015-12-19 04:12:40 -04:00
|
|
|
uint32_t available(void) const {
|
|
|
|
return buffer->available() / sizeof(T);
|
|
|
|
}
|
2016-02-21 21:11:19 -04:00
|
|
|
|
2019-12-06 05:23:54 -04:00
|
|
|
// return number of objects that could be written to the back of the queue
|
2020-02-02 12:13:12 -04:00
|
|
|
// !!! Note ObjectBuffer_TS is a duplicate of this update, in both places !!!
|
2015-12-19 04:12:40 -04:00
|
|
|
uint32_t space(void) const {
|
|
|
|
return buffer->space() / sizeof(T);
|
|
|
|
}
|
2016-02-21 21:11:19 -04:00
|
|
|
|
|
|
|
// true is available() == 0
|
2020-02-02 12:13:12 -04:00
|
|
|
// !!! Note ObjectBuffer_TS is a duplicate of this update, in both places !!!
|
2020-06-03 02:27:49 -03:00
|
|
|
bool is_empty(void) const WARN_IF_UNUSED {
|
2020-06-03 01:40:29 -03:00
|
|
|
return buffer->is_empty();
|
2015-12-19 04:12:40 -04:00
|
|
|
}
|
2016-02-21 21:11:19 -04:00
|
|
|
|
2019-12-06 05:23:54 -04:00
|
|
|
// push one object onto the back of the queue
|
2020-02-02 12:13:12 -04:00
|
|
|
// !!! Note ObjectBuffer_TS is a duplicate of this update, in both places !!!
|
2015-12-19 04:12:40 -04:00
|
|
|
bool push(const T &object) {
|
|
|
|
if (buffer->space() < sizeof(T)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return buffer->write((uint8_t*)&object, sizeof(T)) == sizeof(T);
|
|
|
|
}
|
2016-07-08 16:11:04 -03:00
|
|
|
|
2019-12-06 05:23:54 -04:00
|
|
|
// push N objects onto the back of the queue
|
2020-02-02 12:13:12 -04:00
|
|
|
// !!! Note ObjectBuffer_TS is a duplicate of this update, in both places !!!
|
2018-01-17 18:37:01 -04:00
|
|
|
bool push(const T *object, uint32_t n) {
|
|
|
|
if (buffer->space() < n*sizeof(T)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return buffer->write((uint8_t*)object, n*sizeof(T)) == n*sizeof(T);
|
|
|
|
}
|
|
|
|
|
2016-02-21 21:11:19 -04:00
|
|
|
/*
|
2019-12-06 05:23:54 -04:00
|
|
|
throw away an object from the front of the queue
|
2016-02-21 21:11:19 -04:00
|
|
|
*/
|
2020-02-02 12:13:12 -04:00
|
|
|
// !!! Note ObjectBuffer_TS is a duplicate of this update, in both places !!!
|
2016-02-21 21:11:19 -04:00
|
|
|
bool pop(void) {
|
|
|
|
return buffer->advance(sizeof(T));
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
2019-12-06 05:23:54 -04:00
|
|
|
pop earliest object off the front of the queue
|
2016-02-21 21:11:19 -04:00
|
|
|
*/
|
2020-02-02 12:13:12 -04:00
|
|
|
// !!! Note ObjectBuffer_TS is a duplicate of this update, in both places !!!
|
2020-06-03 02:27:49 -03:00
|
|
|
bool pop(T &object) WARN_IF_UNUSED {
|
2015-12-19 04:12:40 -04:00
|
|
|
if (buffer->available() < sizeof(T)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return buffer->read((uint8_t*)&object, sizeof(T)) == sizeof(T);
|
|
|
|
}
|
|
|
|
|
2016-07-08 16:11:04 -03:00
|
|
|
|
2016-02-21 21:11:19 -04:00
|
|
|
/*
|
2016-02-22 02:13:27 -04:00
|
|
|
* push_force() is semantically equivalent to:
|
|
|
|
* if (!push(t)) { pop(); push(t); }
|
2016-02-21 21:11:19 -04:00
|
|
|
*/
|
2020-02-02 12:13:12 -04:00
|
|
|
// !!! Note ObjectBuffer_TS is a duplicate of this update, in both places !!!
|
2016-02-22 02:13:27 -04:00
|
|
|
bool push_force(const T &object) {
|
2016-02-21 21:11:19 -04:00
|
|
|
if (buffer->space() < sizeof(T)) {
|
|
|
|
buffer->advance(sizeof(T));
|
|
|
|
}
|
|
|
|
return push(object);
|
|
|
|
}
|
|
|
|
|
2018-01-17 18:37:01 -04:00
|
|
|
/*
|
|
|
|
* push_force() N objects
|
|
|
|
*/
|
2020-02-02 12:13:12 -04:00
|
|
|
// !!! Note ObjectBuffer_TS is a duplicate of this update, in both places !!!
|
2018-01-17 18:37:01 -04:00
|
|
|
bool push_force(const T *object, uint32_t n) {
|
|
|
|
uint32_t _space = buffer->space();
|
|
|
|
if (_space < sizeof(T)*n) {
|
|
|
|
buffer->advance(sizeof(T)*(n-_space));
|
|
|
|
}
|
|
|
|
return push(object, n);
|
|
|
|
}
|
|
|
|
|
2016-02-21 21:11:19 -04:00
|
|
|
/*
|
2019-12-06 05:23:54 -04:00
|
|
|
peek copies an object out from the front of the queue without advancing the read pointer
|
2016-02-21 21:11:19 -04:00
|
|
|
*/
|
2020-02-02 12:13:12 -04:00
|
|
|
// !!! Note ObjectBuffer_TS is a duplicate of this update, in both places !!!
|
2020-06-03 02:27:49 -03:00
|
|
|
bool peek(T &object) WARN_IF_UNUSED {
|
2016-02-22 05:22:09 -04:00
|
|
|
return buffer->peekbytes((uint8_t*)&object, sizeof(T)) == sizeof(T);
|
2016-02-21 21:11:19 -04:00
|
|
|
}
|
2016-02-22 03:32:51 -04:00
|
|
|
|
2018-11-03 02:44:15 -03:00
|
|
|
/*
|
|
|
|
return a pointer to first contiguous array of available
|
|
|
|
objects. Return nullptr if none available
|
|
|
|
*/
|
2020-02-02 12:13:12 -04:00
|
|
|
// !!! Note ObjectBuffer_TS is a duplicate of this, update in both places !!!
|
2018-11-03 02:44:15 -03:00
|
|
|
const T *readptr(uint32_t &n) {
|
|
|
|
uint32_t avail_bytes = 0;
|
2021-06-26 07:59:19 -03:00
|
|
|
#pragma GCC diagnostic push
|
|
|
|
#pragma GCC diagnostic ignored "-Wcast-align"
|
2018-11-03 02:44:15 -03:00
|
|
|
const T *ret = (const T *)buffer->readptr(avail_bytes);
|
2021-08-22 05:33:00 -03:00
|
|
|
#pragma GCC diagnostic pop
|
2018-11-03 02:44:15 -03:00
|
|
|
if (!ret || avail_bytes < sizeof(T)) {
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
n = avail_bytes / sizeof(T);
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
|
|
|
// advance the read pointer (discarding objects)
|
2020-02-02 12:13:12 -04:00
|
|
|
// !!! Note ObjectBuffer_TS is a duplicate of this, update in both places !!!
|
2018-11-03 02:44:15 -03:00
|
|
|
bool advance(uint32_t n) {
|
|
|
|
return buffer->advance(n * sizeof(T));
|
|
|
|
}
|
|
|
|
|
2016-02-22 03:32:51 -04:00
|
|
|
/* update the object at the front of the queue (the one that would
|
|
|
|
be fetched by pop()) */
|
2020-02-02 12:13:12 -04:00
|
|
|
// !!! Note ObjectBuffer_TS is a duplicate of this, update in both places !!!
|
2016-02-22 03:32:51 -04:00
|
|
|
bool update(const T &object) {
|
|
|
|
return buffer->update((uint8_t*)&object, sizeof(T));
|
|
|
|
}
|
2016-07-08 16:11:04 -03:00
|
|
|
|
2015-12-19 04:12:40 -04:00
|
|
|
private:
|
|
|
|
ByteBuffer *buffer = nullptr;
|
2020-07-31 10:37:52 -03:00
|
|
|
bool external_buf = true;
|
2016-02-23 18:15:22 -04:00
|
|
|
};
|
2016-07-08 16:11:04 -03:00
|
|
|
|
2020-02-02 12:13:12 -04:00
|
|
|
/*
|
|
|
|
Thread safe ring buffer class for objects of fixed size
|
|
|
|
!!! Note this is a duplicate of ObjectBuffer with semaphore, update in both places !!!
|
|
|
|
*/
|
|
|
|
template <class T>
|
|
|
|
class ObjectBuffer_TS {
|
|
|
|
public:
|
2020-03-05 10:59:25 -04:00
|
|
|
ObjectBuffer_TS(uint32_t _size = 0) {
|
2020-02-02 12:13:12 -04:00
|
|
|
// we set size to 1 more than requested as the byte buffer
|
|
|
|
// gives one less byte than requested. We round up to a full
|
|
|
|
// multiple of the object size so that we always get aligned
|
|
|
|
// elements, which makes the readptr() method possible
|
|
|
|
buffer = new ByteBuffer(((_size+1) * sizeof(T)));
|
|
|
|
}
|
|
|
|
~ObjectBuffer_TS(void) {
|
|
|
|
delete buffer;
|
|
|
|
}
|
|
|
|
|
2020-03-05 10:59:25 -04:00
|
|
|
// return size of ringbuffer
|
2020-09-15 12:53:54 -03:00
|
|
|
uint32_t get_size(void) {
|
2020-03-05 10:59:25 -04:00
|
|
|
WITH_SEMAPHORE(sem);
|
2023-01-01 17:54:16 -04:00
|
|
|
if (buffer == nullptr) {
|
|
|
|
return 0;
|
|
|
|
}
|
2021-01-14 18:57:06 -04:00
|
|
|
uint32_t size = buffer->get_size() / sizeof(T);
|
|
|
|
return size>0?size-1:0;
|
2020-03-05 10:59:25 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// set size of ringbuffer, caller responsible for locking
|
|
|
|
bool set_size(uint32_t size) {
|
|
|
|
WITH_SEMAPHORE(sem);
|
|
|
|
return buffer->set_size(((size+1) * sizeof(T)));
|
|
|
|
}
|
|
|
|
|
|
|
|
// read len objects without advancing the read pointer
|
|
|
|
uint32_t peek(T *data, uint32_t len) {
|
|
|
|
WITH_SEMAPHORE(sem);
|
|
|
|
return buffer->peekbytes((uint8_t*)data, len * sizeof(T)) / sizeof(T);
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2020-02-02 12:13:12 -04:00
|
|
|
// Discards the buffer content, emptying it.
|
|
|
|
// !!! Note this is a duplicate of ObjectBuffer with semaphore, update in both places !!!
|
|
|
|
void clear(void)
|
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(sem);
|
|
|
|
buffer->clear();
|
|
|
|
}
|
|
|
|
|
|
|
|
// return number of objects available to be read from the front of the queue
|
|
|
|
// !!! Note this is a duplicate of ObjectBuffer with semaphore, update in both places !!!
|
|
|
|
uint32_t available(void) {
|
|
|
|
WITH_SEMAPHORE(sem);
|
|
|
|
return buffer->available() / sizeof(T);
|
|
|
|
}
|
|
|
|
|
|
|
|
// return number of objects that could be written to the back of the queue
|
|
|
|
// !!! Note this is a duplicate of ObjectBuffer with semaphore, update in both places !!!
|
|
|
|
uint32_t space(void) {
|
|
|
|
WITH_SEMAPHORE(sem);
|
|
|
|
return buffer->space() / sizeof(T);
|
|
|
|
}
|
|
|
|
|
|
|
|
// true is available() == 0
|
|
|
|
// !!! Note this is a duplicate of ObjectBuffer with semaphore, update in both places !!!
|
2020-06-03 02:27:49 -03:00
|
|
|
bool is_empty(void) WARN_IF_UNUSED {
|
2020-02-02 12:13:12 -04:00
|
|
|
WITH_SEMAPHORE(sem);
|
2020-06-03 01:40:29 -03:00
|
|
|
return buffer->is_empty();
|
2020-02-02 12:13:12 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// push one object onto the back of the queue
|
|
|
|
// !!! Note this is a duplicate of ObjectBuffer with semaphore, update in both places !!!
|
|
|
|
bool push(const T &object) {
|
|
|
|
WITH_SEMAPHORE(sem);
|
|
|
|
if (buffer->space() < sizeof(T)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return buffer->write((uint8_t*)&object, sizeof(T)) == sizeof(T);
|
|
|
|
}
|
|
|
|
|
|
|
|
// push N objects onto the back of the queue
|
|
|
|
// !!! Note this is a duplicate of ObjectBuffer with semaphore, update in both places !!!
|
|
|
|
bool push(const T *object, uint32_t n) {
|
|
|
|
WITH_SEMAPHORE(sem);
|
|
|
|
if (buffer->space() < n*sizeof(T)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return buffer->write((uint8_t*)object, n*sizeof(T)) == n*sizeof(T);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
throw away an object from the front of the queue
|
|
|
|
*/
|
|
|
|
// !!! Note this is a duplicate of ObjectBuffer with semaphore, update in both places !!!
|
|
|
|
bool pop(void) {
|
|
|
|
WITH_SEMAPHORE(sem);
|
|
|
|
return buffer->advance(sizeof(T));
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
pop earliest object off the front of the queue
|
|
|
|
*/
|
|
|
|
// !!! Note this is a duplicate of ObjectBuffer with semaphore, update in both places !!!
|
2020-06-03 02:27:49 -03:00
|
|
|
bool pop(T &object) WARN_IF_UNUSED {
|
2020-02-02 12:13:12 -04:00
|
|
|
WITH_SEMAPHORE(sem);
|
|
|
|
if (buffer->available() < sizeof(T)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return buffer->read((uint8_t*)&object, sizeof(T)) == sizeof(T);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
* push_force() is semantically equivalent to:
|
|
|
|
* if (!push(t)) { pop(); push(t); }
|
|
|
|
*/
|
|
|
|
// !!! Note this is a duplicate of ObjectBuffer with semaphore, update in both places !!!
|
|
|
|
bool push_force(const T &object) {
|
|
|
|
WITH_SEMAPHORE(sem);
|
|
|
|
if (buffer->space() < sizeof(T)) {
|
|
|
|
buffer->advance(sizeof(T));
|
|
|
|
}
|
|
|
|
return push(object);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
* push_force() N objects
|
|
|
|
*/
|
|
|
|
// !!! Note this is a duplicate of ObjectBuffer with semaphore, update in both places !!!
|
|
|
|
bool push_force(const T *object, uint32_t n) {
|
|
|
|
WITH_SEMAPHORE(sem);
|
|
|
|
uint32_t _space = buffer->space();
|
|
|
|
if (_space < sizeof(T)*n) {
|
|
|
|
buffer->advance(sizeof(T)*(n-_space));
|
|
|
|
}
|
|
|
|
return push(object, n);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
peek copies an object out from the front of the queue without advancing the read pointer
|
|
|
|
*/
|
|
|
|
// !!! Note this is a duplicate of ObjectBuffer with semaphore, update in both places !!!
|
2020-06-03 02:27:49 -03:00
|
|
|
bool peek(T &object) WARN_IF_UNUSED {
|
2020-02-02 12:13:12 -04:00
|
|
|
WITH_SEMAPHORE(sem);
|
|
|
|
return buffer->peekbytes((uint8_t*)&object, sizeof(T)) == sizeof(T);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
return a pointer to first contiguous array of available
|
|
|
|
objects. Return nullptr if none available
|
|
|
|
*/
|
|
|
|
// !!! Note this is a duplicate of ObjectBuffer with semaphore, update in both places !!!
|
|
|
|
const T *readptr(uint32_t &n) {
|
|
|
|
WITH_SEMAPHORE(sem);
|
|
|
|
uint32_t avail_bytes = 0;
|
2021-06-26 07:59:19 -03:00
|
|
|
#pragma GCC diagnostic push
|
|
|
|
#pragma GCC diagnostic ignored "-Wcast-align"
|
2020-02-02 12:13:12 -04:00
|
|
|
const T *ret = (const T *)buffer->readptr(avail_bytes);
|
2021-08-22 05:33:00 -03:00
|
|
|
#pragma GCC diagnostic pop
|
2020-02-02 12:13:12 -04:00
|
|
|
if (!ret || avail_bytes < sizeof(T)) {
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
n = avail_bytes / sizeof(T);
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
|
|
|
// advance the read pointer (discarding objects)
|
|
|
|
// !!! Note this is a duplicate of ObjectBuffer with semaphore, update in both places !!!
|
|
|
|
bool advance(uint32_t n) {
|
|
|
|
WITH_SEMAPHORE(sem);
|
|
|
|
return buffer->advance(n * sizeof(T));
|
|
|
|
}
|
2016-02-23 18:15:22 -04:00
|
|
|
|
2020-02-02 12:13:12 -04:00
|
|
|
/* update the object at the front of the queue (the one that would
|
|
|
|
be fetched by pop()) */
|
|
|
|
// !!! Note this is a duplicate of ObjectBuffer with semaphore, update in both places !!!
|
|
|
|
bool update(const T &object) {
|
|
|
|
WITH_SEMAPHORE(sem);
|
|
|
|
return buffer->update((uint8_t*)&object, sizeof(T));
|
|
|
|
}
|
|
|
|
|
|
|
|
private:
|
|
|
|
ByteBuffer *buffer = nullptr;
|
|
|
|
HAL_Semaphore sem;
|
|
|
|
};
|
2016-02-23 18:15:22 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
ring buffer class for objects of fixed size with pointer
|
|
|
|
access. Note that this is not thread safe, buf offers efficient
|
|
|
|
array-like access
|
|
|
|
*/
|
|
|
|
template <class T>
|
|
|
|
class ObjectArray {
|
|
|
|
public:
|
2017-09-18 18:10:35 -03:00
|
|
|
ObjectArray(uint16_t size_) {
|
|
|
|
_size = size_;
|
|
|
|
_head = _count = 0;
|
|
|
|
_buffer = new T[_size];
|
2016-02-23 18:15:22 -04:00
|
|
|
}
|
|
|
|
~ObjectArray(void) {
|
2017-09-18 18:10:35 -03:00
|
|
|
delete[] _buffer;
|
2016-02-23 18:15:22 -04:00
|
|
|
}
|
|
|
|
|
2017-09-16 11:07:11 -03:00
|
|
|
// return total number of objects
|
|
|
|
uint16_t size(void) const {
|
|
|
|
return _size;
|
|
|
|
}
|
|
|
|
|
2016-02-23 18:15:22 -04:00
|
|
|
// return number of objects available to be read
|
|
|
|
uint16_t available(void) const {
|
2017-09-18 18:10:35 -03:00
|
|
|
return _count;
|
2016-02-23 18:15:22 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// return number of objects that could be written
|
|
|
|
uint16_t space(void) const {
|
2017-09-18 18:10:35 -03:00
|
|
|
return _size - _count;
|
2016-02-23 18:15:22 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// true is available() == 0
|
2020-06-03 02:27:49 -03:00
|
|
|
bool is_empty(void) const WARN_IF_UNUSED {
|
2017-09-18 18:10:35 -03:00
|
|
|
return _count == 0;
|
2016-02-23 18:15:22 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// push one object
|
|
|
|
bool push(const T &object) {
|
|
|
|
if (space() == 0) {
|
|
|
|
return false;
|
|
|
|
}
|
2017-09-18 18:10:35 -03:00
|
|
|
_buffer[(_head+_count)%_size] = object;
|
|
|
|
_count++;
|
2016-02-23 18:15:22 -04:00
|
|
|
return true;
|
|
|
|
}
|
2016-07-08 16:11:04 -03:00
|
|
|
|
2016-02-23 18:15:22 -04:00
|
|
|
/*
|
|
|
|
throw away an object
|
|
|
|
*/
|
2020-06-03 02:27:49 -03:00
|
|
|
bool pop(void) WARN_IF_UNUSED {
|
2020-06-03 01:40:29 -03:00
|
|
|
if (is_empty()) {
|
2016-02-23 18:15:22 -04:00
|
|
|
return false;
|
|
|
|
}
|
2017-09-18 18:10:35 -03:00
|
|
|
_head = (_head+1) % _size;
|
|
|
|
_count--;
|
2016-02-23 18:15:22 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2017-04-02 11:54:46 -03:00
|
|
|
// Discards the buffer content, emptying it.
|
|
|
|
void clear(void)
|
|
|
|
{
|
2017-09-18 18:10:35 -03:00
|
|
|
_head = _count = 0;
|
2017-04-02 11:54:46 -03:00
|
|
|
}
|
|
|
|
|
2016-02-23 18:15:22 -04:00
|
|
|
/*
|
|
|
|
pop earliest object off the queue
|
|
|
|
*/
|
2020-06-03 02:27:49 -03:00
|
|
|
bool pop(T &object) WARN_IF_UNUSED {
|
2020-06-03 01:40:29 -03:00
|
|
|
if (is_empty()) {
|
2016-02-23 18:15:22 -04:00
|
|
|
return false;
|
|
|
|
}
|
2017-09-18 18:10:35 -03:00
|
|
|
object = _buffer[_head];
|
2016-02-23 18:15:22 -04:00
|
|
|
return pop();
|
|
|
|
}
|
|
|
|
|
2016-07-08 16:11:04 -03:00
|
|
|
|
2016-02-23 18:15:22 -04:00
|
|
|
/*
|
|
|
|
* push_force() is semantically equivalent to:
|
|
|
|
* if (!push(t)) { pop(); push(t); }
|
|
|
|
*/
|
|
|
|
bool push_force(const T &object) {
|
|
|
|
if (space() == 0) {
|
2020-06-03 02:27:49 -03:00
|
|
|
UNUSED_RESULT(pop());
|
2016-02-23 18:15:22 -04:00
|
|
|
}
|
|
|
|
return push(object);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
remove the Nth element from the array. First element is zero
|
|
|
|
*/
|
|
|
|
bool remove(uint16_t n) {
|
2017-09-18 18:10:35 -03:00
|
|
|
if (n >= _count) {
|
2016-02-23 18:15:22 -04:00
|
|
|
return false;
|
|
|
|
}
|
2017-09-18 18:10:35 -03:00
|
|
|
if (n == _count-1) {
|
2016-02-23 18:15:22 -04:00
|
|
|
// remove last element
|
2017-09-18 18:10:35 -03:00
|
|
|
_count--;
|
2016-02-23 18:15:22 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
if (n == 0) {
|
|
|
|
// remove first element
|
|
|
|
return pop();
|
|
|
|
}
|
|
|
|
// take advantage of the [] operator for simple shift of the array elements
|
2017-09-18 18:10:35 -03:00
|
|
|
for (uint16_t i=n; i<_count-1; i++) {
|
2016-02-23 18:15:22 -04:00
|
|
|
*(*this)[i] = *(*this)[i+1];
|
|
|
|
}
|
2017-09-18 18:10:35 -03:00
|
|
|
_count--;
|
2016-02-23 18:15:22 -04:00
|
|
|
return true;
|
|
|
|
}
|
2016-07-08 16:11:04 -03:00
|
|
|
|
2016-02-23 18:15:22 -04:00
|
|
|
// allow array indexing, based on current head. Returns a pointer
|
2016-10-30 02:24:21 -03:00
|
|
|
// to the object or nullptr
|
2016-02-23 18:15:22 -04:00
|
|
|
T * operator[](uint16_t i) {
|
2017-09-18 18:10:35 -03:00
|
|
|
if (i >= _count) {
|
2016-02-23 18:15:22 -04:00
|
|
|
return nullptr;
|
|
|
|
}
|
2017-09-18 18:10:35 -03:00
|
|
|
return &_buffer[(_head+i)%_size];
|
2016-02-23 18:15:22 -04:00
|
|
|
}
|
2016-07-08 16:11:04 -03:00
|
|
|
|
2016-02-23 18:15:22 -04:00
|
|
|
private:
|
2017-09-18 18:10:35 -03:00
|
|
|
T *_buffer;
|
|
|
|
uint16_t _size; // total buffer size
|
|
|
|
uint16_t _count; // number in buffer now
|
|
|
|
uint16_t _head; // first element
|
2015-12-19 04:12:40 -04:00
|
|
|
};
|
2020-03-05 10:59:25 -04:00
|
|
|
|
|
|
|
typedef ObjectBuffer<float> FloatBuffer;
|
|
|
|
typedef ObjectBuffer_TS<float> FloatBuffer_TS;
|
2021-01-14 18:57:06 -04:00
|
|
|
typedef ObjectArray<float> FloatArray;
|