From 9d3a9c20a86676f8edb57777bdb1d024ddca252a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 7 Jan 2015 08:09:29 +1100 Subject: [PATCH] HAL_VRBrain: use common RingBuffer.h --- libraries/AP_HAL_VRBRAIN/UARTDriver.cpp | 10 +--------- 1 file changed, 1 insertion(+), 9 deletions(-) diff --git a/libraries/AP_HAL_VRBRAIN/UARTDriver.cpp b/libraries/AP_HAL_VRBRAIN/UARTDriver.cpp index 4b9cfcff9e..86df7c1cb7 100644 --- a/libraries/AP_HAL_VRBRAIN/UARTDriver.cpp +++ b/libraries/AP_HAL_VRBRAIN/UARTDriver.cpp @@ -16,6 +16,7 @@ #include #include #include +#include "../AP_HAL/utility/RingBuffer.h" using namespace VRBRAIN; @@ -234,15 +235,6 @@ void VRBRAINUARTDriver::set_blocking_writes(bool blocking) bool VRBRAINUARTDriver::tx_pending() { return false; } -/* - buffer handling macros - */ -#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 - /* return number of bytes available to be read from the buffer */