Browse Source

HAL_PX4: use common RingBuffer.h

master
Andrew Tridgell 10 years ago
parent
commit
0c73dc2440
  1. 10
      libraries/AP_HAL_PX4/UARTDriver.cpp

10
libraries/AP_HAL_PX4/UARTDriver.cpp

@ -16,6 +16,7 @@ @@ -16,6 +16,7 @@
#include <termios.h>
#include <drivers/drv_hrt.h>
#include <assert.h>
#include "../AP_HAL/utility/RingBuffer.h"
using namespace PX4;
@ -236,15 +237,6 @@ void PX4UARTDriver::set_blocking_writes(bool blocking) @@ -236,15 +237,6 @@ void PX4UARTDriver::set_blocking_writes(bool blocking)
bool PX4UARTDriver::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
*/

Loading…
Cancel
Save