mirror of https://github.com/ArduPilot/ardupilot
Add documentation and reformat closer to our current code standard.
Add support for re-opening a port without changing the baudrate or buffer sizes. By passing zero for the parameters that aren't to be changed, code can reconfigure a port without needing to know how it was originally configured. git-svn-id: https://arducopter.googlecode.com/svn/trunk@1462 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
2c0e8515d5
commit
8c9a5d36d8
|
@ -1,4 +1,4 @@
|
|||
// -*- Mode: C++; c-basic-offset: 8; indent-tabs-mode: nil -*-
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
//
|
||||
// Interrupt-driven serial transmit/receive library.
|
||||
//
|
||||
|
@ -43,217 +43,201 @@
|
|||
# define FS_MAX_PORTS 1
|
||||
#endif
|
||||
|
||||
FastSerial::Buffer __FastSerial__rxBuffer[FS_MAX_PORTS];
|
||||
FastSerial::Buffer __FastSerial__txBuffer[FS_MAX_PORTS];
|
||||
|
||||
// Default buffer sizes
|
||||
#define RX_BUFFER_SIZE 128
|
||||
#define TX_BUFFER_SIZE 64
|
||||
#define BUFFER_MAX 512
|
||||
FastSerial::Buffer __FastSerial__rxBuffer[FS_MAX_PORTS];
|
||||
FastSerial::Buffer __FastSerial__txBuffer[FS_MAX_PORTS];
|
||||
|
||||
// Constructor /////////////////////////////////////////////////////////////////
|
||||
|
||||
FastSerial::FastSerial(const uint8_t portNumber,
|
||||
volatile uint8_t *ubrrh,
|
||||
volatile uint8_t *ubrrl,
|
||||
volatile uint8_t *ucsra,
|
||||
volatile uint8_t *ucsrb,
|
||||
const uint8_t u2x,
|
||||
const uint8_t portEnableBits,
|
||||
const uint8_t portTxBits)
|
||||
FastSerial::FastSerial(const uint8_t portNumber, volatile uint8_t *ubrrh, volatile uint8_t *ubrrl,
|
||||
volatile uint8_t *ucsra, volatile uint8_t *ucsrb, const uint8_t u2x,
|
||||
const uint8_t portEnableBits, const uint8_t portTxBits) :
|
||||
_ubrrh(ubrrh),
|
||||
_ubrrl(ubrrl),
|
||||
_ucsra(ucsra),
|
||||
_ucsrb(ucsrb),
|
||||
_u2x(u2x),
|
||||
_portEnableBits(portEnableBits),
|
||||
_portTxBits(portTxBits),
|
||||
_rxBuffer(&__FastSerial__rxBuffer[portNumber]),
|
||||
_txBuffer(&__FastSerial__txBuffer[portNumber])
|
||||
{
|
||||
_ubrrh = ubrrh;
|
||||
_ubrrl = ubrrl;
|
||||
_ucsra = ucsra;
|
||||
_ucsrb = ucsrb;
|
||||
_u2x = u2x;
|
||||
_portEnableBits = portEnableBits;
|
||||
_portTxBits = portTxBits;
|
||||
|
||||
// init buffers
|
||||
_rxBuffer = &__FastSerial__rxBuffer[portNumber];
|
||||
_txBuffer->head = _txBuffer->tail = 0;
|
||||
_txBuffer = &__FastSerial__txBuffer[portNumber];
|
||||
_rxBuffer->head = _rxBuffer->tail = 0;
|
||||
}
|
||||
|
||||
// Public Methods //////////////////////////////////////////////////////////////
|
||||
|
||||
void FastSerial::begin(long baud)
|
||||
{
|
||||
unsigned int rxb, txb;
|
||||
|
||||
// If we are re-configuring an already-open port, preserve the
|
||||
// existing buffer sizes.
|
||||
if (_open) {
|
||||
rxb = _rxBuffer->mask + 1;
|
||||
txb = _txBuffer->mask + 1;
|
||||
} else {
|
||||
rxb = RX_BUFFER_SIZE;
|
||||
txb = TX_BUFFER_SIZE;
|
||||
}
|
||||
|
||||
begin(baud, RX_BUFFER_SIZE, TX_BUFFER_SIZE);
|
||||
begin(baud, 0, 0);
|
||||
}
|
||||
|
||||
void FastSerial::begin(long baud, unsigned int rxSpace, unsigned int txSpace)
|
||||
{
|
||||
uint16_t ubrr;
|
||||
bool use_u2x = true;
|
||||
int ureg, u2;
|
||||
long breg, b2, dreg, d2;
|
||||
uint16_t ubrr;
|
||||
bool use_u2x = true;
|
||||
|
||||
// if we are currently open, close and restart
|
||||
if (_open)
|
||||
end();
|
||||
// if we are currently open...
|
||||
if (_open) {
|
||||
// If the caller wants to preserve the buffer sizing, work out what
|
||||
// it currently is...
|
||||
if (0 == rxSpace)
|
||||
rxSpace = _rxBuffer->mask + 1;
|
||||
if (0 == txSpace)
|
||||
txSpace = _txBuffer->mask + 1;
|
||||
|
||||
// allocate buffers
|
||||
if (!_allocBuffer(_rxBuffer, rxSpace ? : RX_BUFFER_SIZE) ||
|
||||
!_allocBuffer(_txBuffer, txSpace ? : TX_BUFFER_SIZE)) {
|
||||
end();
|
||||
return; // couldn't allocate buffers - fatal
|
||||
}
|
||||
_open = true;
|
||||
// close the port in its current configuration, clears _open
|
||||
end();
|
||||
}
|
||||
|
||||
// allocate buffers
|
||||
if (!_allocBuffer(_rxBuffer, rxSpace ? : _default_rx_buffer_size) || !_allocBuffer(_txBuffer, txSpace ? : _default_tx_buffer_size)) {
|
||||
end();
|
||||
return; // couldn't allocate buffers - fatal
|
||||
}
|
||||
|
||||
// reset buffer pointers
|
||||
_txBuffer->head = _txBuffer->tail = 0;
|
||||
_rxBuffer->head = _rxBuffer->tail = 0;
|
||||
|
||||
// mark the port as open
|
||||
_open = true;
|
||||
|
||||
// If the user has supplied a new baud rate, compute the new UBRR value.
|
||||
if (baud > 0) {
|
||||
#if F_CPU == 16000000UL
|
||||
// hardcoded exception for compatibility with the bootloader shipped
|
||||
// with the Duemilanove and previous boards and the firmware on the 8U2
|
||||
// on the Uno and Mega 2560.
|
||||
if (baud == 57600)
|
||||
use_u2x = false;
|
||||
// hardcoded exception for compatibility with the bootloader shipped
|
||||
// with the Duemilanove and previous boards and the firmware on the 8U2
|
||||
// on the Uno and Mega 2560.
|
||||
if (baud == 57600)
|
||||
use_u2x = false;
|
||||
#endif
|
||||
|
||||
if (use_u2x) {
|
||||
ubrr = (F_CPU / 4 / baud - 1) / 2;
|
||||
} else {
|
||||
ubrr = (F_CPU / 8 / baud - 1) / 2;
|
||||
}
|
||||
if (use_u2x) {
|
||||
ubrr = (F_CPU / 4 / baud - 1) / 2;
|
||||
} else {
|
||||
ubrr = (F_CPU / 8 / baud - 1) / 2;
|
||||
}
|
||||
|
||||
*_ucsra = use_u2x ? _BV(_u2x) : 0;
|
||||
*_ubrrh = ubrr >> 8;
|
||||
*_ubrrl = ubrr;
|
||||
*_ucsrb |= _portEnableBits;
|
||||
*_ucsra = use_u2x ? _BV(_u2x) : 0;
|
||||
*_ubrrh = ubrr >> 8;
|
||||
*_ubrrl = ubrr;
|
||||
}
|
||||
|
||||
*_ucsrb |= _portEnableBits;
|
||||
}
|
||||
|
||||
void FastSerial::end()
|
||||
{
|
||||
*_ucsrb &= ~(_portEnableBits | _portTxBits);
|
||||
*_ucsrb &= ~(_portEnableBits | _portTxBits);
|
||||
|
||||
_freeBuffer(_rxBuffer);
|
||||
_freeBuffer(_txBuffer);
|
||||
_open = false;
|
||||
_freeBuffer(_rxBuffer);
|
||||
_freeBuffer(_txBuffer);
|
||||
_open = false;
|
||||
}
|
||||
|
||||
int
|
||||
FastSerial::available(void)
|
||||
int FastSerial::available(void)
|
||||
{
|
||||
if (!_open)
|
||||
return(-1);
|
||||
return((_rxBuffer->head - _rxBuffer->tail) & _rxBuffer->mask);
|
||||
if (!_open)
|
||||
return (-1);
|
||||
return ((_rxBuffer->head - _rxBuffer->tail) & _rxBuffer->mask);
|
||||
}
|
||||
|
||||
int
|
||||
FastSerial::read(void)
|
||||
int FastSerial::read(void)
|
||||
{
|
||||
uint8_t c;
|
||||
uint8_t c;
|
||||
|
||||
// if the head and tail are equal, the buffer is empty
|
||||
if (!_open || (_rxBuffer->head == _rxBuffer->tail))
|
||||
return(-1);
|
||||
// if the head and tail are equal, the buffer is empty
|
||||
if (!_open || (_rxBuffer->head == _rxBuffer->tail))
|
||||
return (-1);
|
||||
|
||||
// pull character from tail
|
||||
c = _rxBuffer->bytes[_rxBuffer->tail];
|
||||
_rxBuffer->tail = (_rxBuffer->tail + 1) & _rxBuffer->mask;
|
||||
// pull character from tail
|
||||
c = _rxBuffer->bytes[_rxBuffer->tail];
|
||||
_rxBuffer->tail = (_rxBuffer->tail + 1) & _rxBuffer->mask;
|
||||
|
||||
return(c);
|
||||
return (c);
|
||||
}
|
||||
|
||||
int
|
||||
FastSerial::peek(void)
|
||||
int FastSerial::peek(void)
|
||||
{
|
||||
|
||||
// if the head and tail are equal, the buffer is empty
|
||||
if (!_open || (_rxBuffer->head == _rxBuffer->tail))
|
||||
return(-1);
|
||||
// if the head and tail are equal, the buffer is empty
|
||||
if (!_open || (_rxBuffer->head == _rxBuffer->tail))
|
||||
return (-1);
|
||||
|
||||
// pull character from tail
|
||||
return(_rxBuffer->bytes[_rxBuffer->tail]);
|
||||
// pull character from tail
|
||||
return (_rxBuffer->bytes[_rxBuffer->tail]);
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
FastSerial::flush(void)
|
||||
void FastSerial::flush(void)
|
||||
{
|
||||
// don't reverse this or there may be problems if the RX interrupt
|
||||
// occurs after reading the value of _rxBuffer->head but before writing
|
||||
// the value to _rxBuffer->tail; the previous value of head
|
||||
// may be written to tail, making it appear as if the buffer
|
||||
// don't reverse this or there may be problems if the RX interrupt
|
||||
// occurs after reading the value of head but before writing
|
||||
// the value to tail; the previous value of rx_buffer_head
|
||||
// may be written to tail, making it appear as if the buffer
|
||||
// were full, not empty.
|
||||
_rxBuffer->head = _rxBuffer->tail;
|
||||
// don't reverse this or there may be problems if the RX interrupt
|
||||
// occurs after reading the value of _rxBuffer->head but before writing
|
||||
// the value to _rxBuffer->tail; the previous value of head
|
||||
// may be written to tail, making it appear as if the buffer
|
||||
// don't reverse this or there may be problems if the RX interrupt
|
||||
// occurs after reading the value of head but before writing
|
||||
// the value to tail; the previous value of rx_buffer_head
|
||||
// may be written to tail, making it appear as if the buffer
|
||||
// were full, not empty.
|
||||
_rxBuffer->head = _rxBuffer->tail;
|
||||
|
||||
// don't reverse this or there may be problems if the TX interrupt
|
||||
// occurs after reading the value of _txBuffer->tail but before writing
|
||||
// the value to _txBuffer->head.
|
||||
_txBuffer->tail = _rxBuffer->head;
|
||||
// don't reverse this or there may be problems if the TX interrupt
|
||||
// occurs after reading the value of _txBuffer->tail but before writing
|
||||
// the value to _txBuffer->head.
|
||||
_txBuffer->tail = _rxBuffer->head;
|
||||
}
|
||||
|
||||
void
|
||||
FastSerial::write(uint8_t c)
|
||||
void FastSerial::write(uint8_t c)
|
||||
{
|
||||
int16_t i;
|
||||
int16_t i;
|
||||
|
||||
if (!_open) // drop bytes if not open
|
||||
return;
|
||||
if (!_open) // drop bytes if not open
|
||||
return;
|
||||
|
||||
// wait for room in the tx buffer
|
||||
i = (_txBuffer->head + 1) & _txBuffer->mask;
|
||||
while (i == _txBuffer->tail)
|
||||
;
|
||||
// wait for room in the tx buffer
|
||||
i = (_txBuffer->head + 1) & _txBuffer->mask;
|
||||
while (i == _txBuffer->tail)
|
||||
;
|
||||
|
||||
// add byte to the buffer
|
||||
_txBuffer->bytes[_txBuffer->head] = c;
|
||||
_txBuffer->head = i;
|
||||
// add byte to the buffer
|
||||
_txBuffer->bytes[_txBuffer->head] = c;
|
||||
_txBuffer->head = i;
|
||||
|
||||
// enable the data-ready interrupt, as it may be off if the buffer is empty
|
||||
*_ucsrb |= _portTxBits;
|
||||
// enable the data-ready interrupt, as it may be off if the buffer is empty
|
||||
*_ucsrb |= _portTxBits;
|
||||
}
|
||||
|
||||
// Buffer management ///////////////////////////////////////////////////////////
|
||||
|
||||
bool
|
||||
FastSerial::_allocBuffer(Buffer *buffer, unsigned int size)
|
||||
bool FastSerial::_allocBuffer(Buffer *buffer, unsigned int size)
|
||||
{
|
||||
uint8_t shift;
|
||||
uint8_t shift;
|
||||
|
||||
// init buffer state
|
||||
buffer->head = buffer->tail = 0;
|
||||
// init buffer state
|
||||
buffer->head = buffer->tail = 0;
|
||||
|
||||
// Compute the power of 2 greater or equal to the requested buffer size
|
||||
// and then a mask to simplify wrapping operations. Using __builtin_clz
|
||||
// would seem to make sense, but it uses a 256(!) byte table.
|
||||
// Note that we ignore requests for more than BUFFER_MAX space.
|
||||
for (shift = 1; (1U << shift) < min(BUFFER_MAX, size); shift++)
|
||||
;
|
||||
buffer->mask = (1 << shift) - 1;
|
||||
// Compute the power of 2 greater or equal to the requested buffer size
|
||||
// and then a mask to simplify wrapping operations. Using __builtin_clz
|
||||
// would seem to make sense, but it uses a 256(!) byte table.
|
||||
// Note that we ignore requests for more than BUFFER_MAX space.
|
||||
for (shift = 1; (1U << shift) < min(_max_buffer_size, size); shift++)
|
||||
;
|
||||
buffer->mask = (1 << shift) - 1;
|
||||
|
||||
// allocate memory for the buffer - if this fails, we fail
|
||||
buffer->bytes = (uint8_t *)malloc(buffer->mask + 1);
|
||||
// allocate memory for the buffer - if this fails, we fail
|
||||
if (buffer->bytes)
|
||||
free(buffer->bytes);
|
||||
buffer->bytes = (uint8_t *) malloc(buffer->mask + 1);
|
||||
|
||||
return(buffer->bytes != NULL);
|
||||
return (buffer->bytes != NULL);
|
||||
}
|
||||
|
||||
void
|
||||
FastSerial::_freeBuffer(Buffer *buffer)
|
||||
void FastSerial::_freeBuffer(Buffer *buffer)
|
||||
{
|
||||
buffer->head = buffer->tail = 0;
|
||||
buffer->mask = 0;
|
||||
if (NULL != buffer->bytes) {
|
||||
free(buffer->bytes);
|
||||
buffer->bytes = NULL;
|
||||
}
|
||||
buffer->head = buffer->tail = 0;
|
||||
buffer->mask = 0;
|
||||
if (NULL != buffer->bytes) {
|
||||
free(buffer->bytes);
|
||||
buffer->bytes = NULL;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -1,10 +1,10 @@
|
|||
// -*- Mode: C++; c-basic-offset: 8; indent-tabs-mode: nil -*-
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
//
|
||||
// Interrupt-driven serial transmit/receive library.
|
||||
//
|
||||
// Copyright (c) 2010 Michael Smith. All rights reserved.
|
||||
//
|
||||
// Receive and baudrate calculations derived from the Arduino
|
||||
// Receive and baudrate calculations derived from the Arduino
|
||||
// HardwareSerial driver:
|
||||
//
|
||||
// Copyright (c) 2006 Nicholas Zambetti. All right reserved.
|
||||
|
@ -35,7 +35,7 @@
|
|||
// Note that this library does not pre-declare drivers for serial
|
||||
// ports; the user must explicitly create drivers for the ports they
|
||||
// wish to use. This is less friendly than the stock Arduino driver,
|
||||
// but it saves 24 bytes of RAM for every unused port and frees up
|
||||
// but it saves a few bytes of RAM for every unused port and frees up
|
||||
// the vector for another driver (e.g. MSPIM on USARTs).
|
||||
//
|
||||
|
||||
|
@ -55,97 +55,150 @@
|
|||
|
||||
#include "BetterStream.h"
|
||||
|
||||
//
|
||||
// Because Arduino libraries aren't really libraries, but we want to
|
||||
// only define interrupt handlers for serial ports that are actually
|
||||
// used, we have to force our users to define them using a macro.
|
||||
//
|
||||
// FastSerialPort(<port name>, <port number>)
|
||||
//
|
||||
// <port name> is the name of the object that will be created by the
|
||||
// macro. <port number> is the 0-based number of the port that will
|
||||
// be managed by the object.
|
||||
//
|
||||
// Previously ports were defined with a different macro for each port,
|
||||
// and these macros are retained for compatibility:
|
||||
//
|
||||
// FastSerialPort0(<port name>) creates <port name> referencing serial port 0
|
||||
// FastSerialPort1(<port name>) creates <port name> referencing serial port 1
|
||||
// FastSerialPort2(<port name>) creates <port name> referencing serial port 2
|
||||
// FastSerialPort3(<port name>) creates <port name> referencing serial port 3
|
||||
//
|
||||
// Note that compatibility macros are only defined for ports that
|
||||
// exist on the target device.
|
||||
//
|
||||
/// @file FastSerial.h
|
||||
/// @brief An enhanced version of the Arduino HardwareSerial class
|
||||
/// implementing interrupt-driven transmission and flexible
|
||||
/// buffer management.
|
||||
///
|
||||
/// Because Arduino libraries aren't really libraries, but we want to
|
||||
/// only define interrupt handlers for serial ports that are actually
|
||||
/// used, we have to force our users to define them using a macro.
|
||||
///
|
||||
/// FastSerialPort(<port name>, <port number>)
|
||||
///
|
||||
/// <port name> is the name of the object that will be created by the
|
||||
/// macro. <port number> is the 0-based number of the port that will
|
||||
/// be managed by the object.
|
||||
///
|
||||
/// Previously ports were defined with a different macro for each port,
|
||||
/// and these macros are retained for compatibility:
|
||||
///
|
||||
/// FastSerialPort0(<port name>) creates <port name> referencing serial port 0
|
||||
/// FastSerialPort1(<port name>) creates <port name> referencing serial port 1
|
||||
/// FastSerialPort2(<port name>) creates <port name> referencing serial port 2
|
||||
/// FastSerialPort3(<port name>) creates <port name> referencing serial port 3
|
||||
///
|
||||
/// Note that compatibility macros are only defined for ports that
|
||||
/// exist on the target device.
|
||||
///
|
||||
|
||||
//
|
||||
// Forward declarations for clients that want to assume that the
|
||||
// default Serial* objects exist.
|
||||
//
|
||||
// Note that the application is responsible for ensuring that these
|
||||
// actually get defined, otherwise Arduino will suck in the
|
||||
// HardwareSerial library and linking will fail.
|
||||
//
|
||||
/// @name Compatibility
|
||||
///
|
||||
/// Forward declarations for clients that want to assume that the
|
||||
/// default Serial* objects exist.
|
||||
///
|
||||
/// Note that the application is responsible for ensuring that these
|
||||
/// actually get defined, otherwise Arduino will suck in the
|
||||
/// HardwareSerial library and linking will fail.
|
||||
//@{
|
||||
extern class FastSerial Serial;
|
||||
extern class FastSerial Serial1;
|
||||
extern class FastSerial Serial2;
|
||||
extern class FastSerial Serial3;
|
||||
//@}
|
||||
|
||||
class FastSerial : public BetterStream {
|
||||
/// The FastSerial class definition
|
||||
///
|
||||
class FastSerial: public BetterStream {
|
||||
public:
|
||||
FastSerial(const uint8_t portNumber,
|
||||
volatile uint8_t *ubrrh,
|
||||
volatile uint8_t *ubrrl,
|
||||
volatile uint8_t *ucsra,
|
||||
volatile uint8_t *ucsrb,
|
||||
const uint8_t u2x,
|
||||
const uint8_t portEnableBits,
|
||||
const uint8_t portTxBits);
|
||||
/// Constructor
|
||||
FastSerial(const uint8_t portNumber, volatile uint8_t *ubrrh, volatile uint8_t *ubrrl, volatile uint8_t *ucsra,
|
||||
volatile uint8_t *ucsrb, const uint8_t u2x, const uint8_t portEnableBits, const uint8_t portTxBits);
|
||||
|
||||
// Serial API
|
||||
virtual void begin(long baud);
|
||||
virtual void begin(long baud, unsigned int rxSpace, unsigned int txSpace);
|
||||
virtual void end(void);
|
||||
virtual int available(void);
|
||||
virtual int read(void);
|
||||
virtual int peek(void);
|
||||
virtual void flush(void);
|
||||
virtual void write(uint8_t c);
|
||||
using BetterStream::write;
|
||||
/// @name Serial API
|
||||
//@{
|
||||
virtual void begin(long baud);
|
||||
virtual void end(void);
|
||||
virtual int available(void);
|
||||
virtual int read(void);
|
||||
virtual int peek(void);
|
||||
virtual void flush(void);
|
||||
virtual void write(uint8_t c);
|
||||
using BetterStream::write;
|
||||
//@}
|
||||
|
||||
// public so the interrupt handlers can see it
|
||||
struct Buffer {
|
||||
volatile uint16_t head, tail;
|
||||
uint16_t mask;
|
||||
uint8_t *bytes;
|
||||
};
|
||||
/// Extended port open method
|
||||
///
|
||||
/// Allows for both opening with specified buffer sizes, and re-opening
|
||||
/// to adjust a subset of the port's settings.
|
||||
///
|
||||
/// @note Buffer sizes greater than ::_max_buffer_size will be rounded
|
||||
/// down.
|
||||
///
|
||||
/// @param baud Selects the speed that the port will be
|
||||
/// configured to. If zero, the port speed is left
|
||||
/// unchanged.
|
||||
/// @param rxSpace Sets the receive buffer size for the port. If zero
|
||||
/// then the buffer size is left unchanged if the port
|
||||
/// is open, or set to ::_default_rx_buffer_size if it is
|
||||
/// currently closed.
|
||||
/// @param txSpace Sets the transmit buffer size for the port. If zero
|
||||
/// then the buffer size is left unchanged if the port
|
||||
/// is open, or set to ::_default_tx_buffer_size if it
|
||||
/// is currently closed.
|
||||
///
|
||||
virtual void begin(long baud, unsigned int rxSpace, unsigned int txSpace);
|
||||
|
||||
/// Transmit/receive buffer descriptor.
|
||||
///
|
||||
/// Public so the interrupt handlers can see it
|
||||
struct Buffer {
|
||||
volatile uint16_t head, tail; ///< head and tail pointers
|
||||
uint16_t mask; ///< buffer size mask for pointer wrap
|
||||
uint8_t *bytes; ///< pointer to allocated buffer
|
||||
};
|
||||
|
||||
private:
|
||||
// register accessors
|
||||
volatile uint8_t *_ubrrh;
|
||||
volatile uint8_t *_ubrrl;
|
||||
volatile uint8_t *_ucsra;
|
||||
volatile uint8_t *_ucsrb;
|
||||
// register accessors
|
||||
volatile uint8_t * const _ubrrh;
|
||||
volatile uint8_t * const _ubrrl;
|
||||
volatile uint8_t * const _ucsra;
|
||||
volatile uint8_t * const _ucsrb;
|
||||
|
||||
// register magic numbers
|
||||
uint8_t _portEnableBits; // rx, tx and rx interrupt enables
|
||||
uint8_t _portTxBits; // tx data and completion interrupt enables
|
||||
uint8_t _u2x;
|
||||
// register magic numbers
|
||||
const uint8_t _portEnableBits; ///< rx, tx and rx interrupt enables
|
||||
const uint8_t _portTxBits; ///< tx data and completion interrupt enables
|
||||
const uint8_t _u2x;
|
||||
|
||||
// ring buffers
|
||||
Buffer *_rxBuffer;
|
||||
Buffer *_txBuffer;
|
||||
bool _open;
|
||||
// ring buffers
|
||||
Buffer * const _rxBuffer;
|
||||
Buffer * const _txBuffer;
|
||||
bool _open;
|
||||
|
||||
static bool _allocBuffer(Buffer *buffer, unsigned int size);
|
||||
static void _freeBuffer(Buffer *buffer);
|
||||
/// Allocates a buffer of the given size
|
||||
///
|
||||
/// @param buffer The buffer descriptor for which the buffer will
|
||||
/// will be allocated.
|
||||
/// @param size The desired buffer size.
|
||||
/// @returns True if the buffer was allocated successfully.
|
||||
///
|
||||
static bool _allocBuffer(Buffer *buffer, unsigned int size);
|
||||
|
||||
/// Frees the allocated buffer in a descriptor
|
||||
///
|
||||
/// @param buffer The descriptor whose buffer should be freed.
|
||||
///
|
||||
static void _freeBuffer(Buffer *buffer);
|
||||
|
||||
/// default receive buffer size
|
||||
static const unsigned int _default_rx_buffer_size = 128;
|
||||
|
||||
/// default transmit buffer size
|
||||
static const unsigned int _default_tx_buffer_size = 16;
|
||||
|
||||
/// maxium tx/rx buffer size
|
||||
/// @note if we could bring the max size down to 256, the mask and head/tail
|
||||
/// pointers in the buffer could become uint8_t.
|
||||
///
|
||||
static const unsigned int _max_buffer_size = 512;
|
||||
};
|
||||
|
||||
// Used by the per-port interrupt vectors
|
||||
extern FastSerial::Buffer __FastSerial__rxBuffer[];
|
||||
extern FastSerial::Buffer __FastSerial__txBuffer[];
|
||||
extern FastSerial::Buffer __FastSerial__rxBuffer[];
|
||||
extern FastSerial::Buffer __FastSerial__txBuffer[];
|
||||
|
||||
// Generic Rx/Tx vectors for a serial port - needs to know magic numbers
|
||||
/// Generic Rx/Tx vectors for a serial port - needs to know magic numbers
|
||||
///
|
||||
#define FastSerialHandler(_PORT, _RXVECTOR, _TXVECTOR, _UDR, _UCSRB, _TXBITS) \
|
||||
ISR(_RXVECTOR, ISR_BLOCK) \
|
||||
{ \
|
||||
|
@ -215,9 +268,9 @@ struct hack
|
|||
# endif
|
||||
#endif
|
||||
|
||||
//
|
||||
// Macro defining a FastSerial port instance.
|
||||
//
|
||||
///
|
||||
/// Macro defining a FastSerial port instance.
|
||||
///
|
||||
#define FastSerialPort(_name, _num) \
|
||||
FastSerial _name(_num, \
|
||||
&UBRR##_num##H, \
|
||||
|
@ -234,14 +287,14 @@ struct hack
|
|||
UCSR##_num##B, \
|
||||
_BV(UDRIE##_num))
|
||||
|
||||
//
|
||||
// Compatibility macros for previous FastSerial versions.
|
||||
//
|
||||
// Note that these are not conditionally defined, as the errors
|
||||
// generated when using these macros for a board that does not support
|
||||
// the port are better than the errors generated for a macro that's not
|
||||
// defined at all.
|
||||
//
|
||||
///
|
||||
/// Compatibility macros for previous FastSerial versions.
|
||||
///
|
||||
/// Note that these are not conditionally defined, as the errors
|
||||
/// generated when using these macros for a board that does not support
|
||||
/// the port are better than the errors generated for a macro that's not
|
||||
/// defined at all.
|
||||
///
|
||||
#define FastSerialPort0(_portName) FastSerialPort(_portName, 0)
|
||||
#define FastSerialPort1(_portName) FastSerialPort(_portName, 1)
|
||||
#define FastSerialPort2(_portName) FastSerialPort(_portName, 2)
|
||||
|
|
Loading…
Reference in New Issue