mirror of https://github.com/ArduPilot/ardupilot
RingBuffer: Remove 'old style' version
This commit is contained in:
parent
c112e1c889
commit
3f1896b9b7
|
@ -1,31 +1,11 @@
|
|||
#pragma once
|
||||
|
||||
#include <atomic>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
/*
|
||||
old style ring buffer handling macros
|
||||
|
||||
These macros assume a ring buffer like this:
|
||||
|
||||
uint8_t *_buf;
|
||||
uint16_t _buf_size;
|
||||
volatile uint16_t _buf_head;
|
||||
volatile uint16_t _buf_tail;
|
||||
|
||||
These should be converted to a class in future
|
||||
*/
|
||||
#define BUF_AVAILABLE(buf) ((buf##_head > (_tail=buf##_tail))? (buf##_size - buf##_head) + _tail: _tail - buf##_head)
|
||||
#define BUF_SPACE(buf) (((_head=buf##_head) > buf##_tail)?(_head - buf##_tail) - 1:((buf##_size - buf##_tail) + _head) - 1)
|
||||
#define BUF_EMPTY(buf) (buf##_head == buf##_tail)
|
||||
#define BUF_ADVANCETAIL(buf, n) buf##_tail = (buf##_tail + n) % buf##_size
|
||||
#define BUF_ADVANCEHEAD(buf, n) buf##_head = (buf##_head + n) % buf##_size
|
||||
|
||||
|
||||
/*
|
||||
new style buffers
|
||||
* Circular buffer of bytes.
|
||||
*/
|
||||
class ByteBuffer {
|
||||
public:
|
||||
|
@ -108,10 +88,8 @@ private:
|
|||
uint8_t *buf;
|
||||
uint32_t size;
|
||||
|
||||
// head is where the next available data is. tail is where new
|
||||
// data is written
|
||||
std::atomic<uint32_t> head{0};
|
||||
std::atomic<uint32_t> tail{0};
|
||||
std::atomic<uint32_t> head{0}; // where to read data
|
||||
std::atomic<uint32_t> tail{0}; // where to write data
|
||||
};
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue