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:
DrZiplok@gmail.com 2011-01-10 01:17:03 +00:00
parent 2c0e8515d5
commit 8c9a5d36d8
2 changed files with 274 additions and 237 deletions

View File

@ -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. // Interrupt-driven serial transmit/receive library.
// //
@ -46,75 +46,63 @@
FastSerial::Buffer __FastSerial__rxBuffer[FS_MAX_PORTS]; FastSerial::Buffer __FastSerial__rxBuffer[FS_MAX_PORTS];
FastSerial::Buffer __FastSerial__txBuffer[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
// Constructor ///////////////////////////////////////////////////////////////// // Constructor /////////////////////////////////////////////////////////////////
FastSerial::FastSerial(const uint8_t portNumber, FastSerial::FastSerial(const uint8_t portNumber, volatile uint8_t *ubrrh, volatile uint8_t *ubrrl,
volatile uint8_t *ubrrh, volatile uint8_t *ucsra, volatile uint8_t *ucsrb, const uint8_t u2x,
volatile uint8_t *ubrrl, const uint8_t portEnableBits, const uint8_t portTxBits) :
volatile uint8_t *ucsra, _ubrrh(ubrrh),
volatile uint8_t *ucsrb, _ubrrl(ubrrl),
const uint8_t u2x, _ucsra(ucsra),
const uint8_t portEnableBits, _ucsrb(ucsrb),
const uint8_t portTxBits) _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 ////////////////////////////////////////////////////////////// // Public Methods //////////////////////////////////////////////////////////////
void FastSerial::begin(long baud) void FastSerial::begin(long baud)
{ {
unsigned int rxb, txb; begin(baud, 0, 0);
// 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);
} }
void FastSerial::begin(long baud, unsigned int rxSpace, unsigned int txSpace) void FastSerial::begin(long baud, unsigned int rxSpace, unsigned int txSpace)
{ {
uint16_t ubrr; uint16_t ubrr;
bool use_u2x = true; bool use_u2x = true;
int ureg, u2;
long breg, b2, dreg, d2;
// if we are currently open, close and restart // if we are currently open...
if (_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;
// close the port in its current configuration, clears _open
end(); end();
}
// allocate buffers // allocate buffers
if (!_allocBuffer(_rxBuffer, rxSpace ? : RX_BUFFER_SIZE) || if (!_allocBuffer(_rxBuffer, rxSpace ? : _default_rx_buffer_size) || !_allocBuffer(_txBuffer, txSpace ? : _default_tx_buffer_size)) {
!_allocBuffer(_txBuffer, txSpace ? : TX_BUFFER_SIZE)) {
end(); end();
return; // couldn't allocate buffers - fatal 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; _open = true;
// If the user has supplied a new baud rate, compute the new UBRR value.
if (baud > 0) {
#if F_CPU == 16000000UL #if F_CPU == 16000000UL
// hardcoded exception for compatibility with the bootloader shipped // hardcoded exception for compatibility with the bootloader shipped
// with the Duemilanove and previous boards and the firmware on the 8U2 // with the Duemilanove and previous boards and the firmware on the 8U2
@ -132,6 +120,8 @@ void FastSerial::begin(long baud, unsigned int rxSpace, unsigned int txSpace)
*_ucsra = use_u2x ? _BV(_u2x) : 0; *_ucsra = use_u2x ? _BV(_u2x) : 0;
*_ubrrh = ubrr >> 8; *_ubrrh = ubrr >> 8;
*_ubrrl = ubrr; *_ubrrl = ubrr;
}
*_ucsrb |= _portEnableBits; *_ucsrb |= _portEnableBits;
} }
@ -144,16 +134,14 @@ void FastSerial::end()
_open = false; _open = false;
} }
int int FastSerial::available(void)
FastSerial::available(void)
{ {
if (!_open) if (!_open)
return (-1); return (-1);
return ((_rxBuffer->head - _rxBuffer->tail) & _rxBuffer->mask); return ((_rxBuffer->head - _rxBuffer->tail) & _rxBuffer->mask);
} }
int int FastSerial::read(void)
FastSerial::read(void)
{ {
uint8_t c; uint8_t c;
@ -168,8 +156,7 @@ FastSerial::read(void)
return (c); return (c);
} }
int int FastSerial::peek(void)
FastSerial::peek(void)
{ {
// if the head and tail are equal, the buffer is empty // if the head and tail are equal, the buffer is empty
@ -180,9 +167,7 @@ FastSerial::peek(void)
return (_rxBuffer->bytes[_rxBuffer->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 // don't reverse this or there may be problems if the RX interrupt
// occurs after reading the value of _rxBuffer->head but before writing // occurs after reading the value of _rxBuffer->head but before writing
@ -201,8 +186,7 @@ FastSerial::flush(void)
_txBuffer->tail = _rxBuffer->head; _txBuffer->tail = _rxBuffer->head;
} }
void void FastSerial::write(uint8_t c)
FastSerial::write(uint8_t c)
{ {
int16_t i; int16_t i;
@ -224,8 +208,7 @@ FastSerial::write(uint8_t c)
// Buffer management /////////////////////////////////////////////////////////// // Buffer management ///////////////////////////////////////////////////////////
bool bool FastSerial::_allocBuffer(Buffer *buffer, unsigned int size)
FastSerial::_allocBuffer(Buffer *buffer, unsigned int size)
{ {
uint8_t shift; uint8_t shift;
@ -236,18 +219,19 @@ FastSerial::_allocBuffer(Buffer *buffer, unsigned int size)
// and then a mask to simplify wrapping operations. Using __builtin_clz // and then a mask to simplify wrapping operations. Using __builtin_clz
// would seem to make sense, but it uses a 256(!) byte table. // would seem to make sense, but it uses a 256(!) byte table.
// Note that we ignore requests for more than BUFFER_MAX space. // Note that we ignore requests for more than BUFFER_MAX space.
for (shift = 1; (1U << shift) < min(BUFFER_MAX, size); shift++) for (shift = 1; (1U << shift) < min(_max_buffer_size, size); shift++)
; ;
buffer->mask = (1 << shift) - 1; buffer->mask = (1 << shift) - 1;
// allocate memory for the buffer - if this fails, we fail // allocate memory for the buffer - if this fails, we fail
if (buffer->bytes)
free(buffer->bytes);
buffer->bytes = (uint8_t *) malloc(buffer->mask + 1); buffer->bytes = (uint8_t *) malloc(buffer->mask + 1);
return (buffer->bytes != NULL); return (buffer->bytes != NULL);
} }
void void FastSerial::_freeBuffer(Buffer *buffer)
FastSerial::_freeBuffer(Buffer *buffer)
{ {
buffer->head = buffer->tail = 0; buffer->head = buffer->tail = 0;
buffer->mask = 0; buffer->mask = 0;

View File

@ -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. // Interrupt-driven serial transmit/receive library.
// //
@ -35,7 +35,7 @@
// Note that this library does not pre-declare drivers for serial // Note that this library does not pre-declare drivers for serial
// ports; the user must explicitly create drivers for the ports they // ports; the user must explicitly create drivers for the ports they
// wish to use. This is less friendly than the stock Arduino driver, // 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). // the vector for another driver (e.g. MSPIM on USARTs).
// //
@ -55,56 +55,59 @@
#include "BetterStream.h" #include "BetterStream.h"
// /// @file FastSerial.h
// Because Arduino libraries aren't really libraries, but we want to /// @brief An enhanced version of the Arduino HardwareSerial class
// only define interrupt handlers for serial ports that are actually /// implementing interrupt-driven transmission and flexible
// used, we have to force our users to define them using a macro. /// buffer management.
// ///
// FastSerialPort(<port name>, <port number>) /// Because Arduino libraries aren't really libraries, but we want to
// /// only define interrupt handlers for serial ports that are actually
// <port name> is the name of the object that will be created by the /// used, we have to force our users to define them using a macro.
// macro. <port number> is the 0-based number of the port that will ///
// be managed by the object. /// FastSerialPort(<port name>, <port number>)
// ///
// Previously ports were defined with a different macro for each port, /// <port name> is the name of the object that will be created by the
// and these macros are retained for compatibility: /// macro. <port number> is the 0-based number of the port that will
// /// be managed by the object.
// FastSerialPort0(<port name>) creates <port name> referencing serial port 0 ///
// FastSerialPort1(<port name>) creates <port name> referencing serial port 1 /// Previously ports were defined with a different macro for each port,
// FastSerialPort2(<port name>) creates <port name> referencing serial port 2 /// and these macros are retained for compatibility:
// FastSerialPort3(<port name>) creates <port name> referencing serial port 3 ///
// /// FastSerialPort0(<port name>) creates <port name> referencing serial port 0
// Note that compatibility macros are only defined for ports that /// FastSerialPort1(<port name>) creates <port name> referencing serial port 1
// exist on the target device. /// 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.
///
// /// @name Compatibility
// Forward declarations for clients that want to assume that the ///
// default Serial* objects exist. /// 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 /// Note that the application is responsible for ensuring that these
// HardwareSerial library and linking will fail. /// actually get defined, otherwise Arduino will suck in the
// /// HardwareSerial library and linking will fail.
//@{
extern class FastSerial Serial; extern class FastSerial Serial;
extern class FastSerial Serial1; extern class FastSerial Serial1;
extern class FastSerial Serial2; extern class FastSerial Serial2;
extern class FastSerial Serial3; extern class FastSerial Serial3;
//@}
/// The FastSerial class definition
///
class FastSerial: public BetterStream { class FastSerial: public BetterStream {
public: public:
FastSerial(const uint8_t portNumber, /// Constructor
volatile uint8_t *ubrrh, FastSerial(const uint8_t portNumber, volatile uint8_t *ubrrh, volatile uint8_t *ubrrl, volatile uint8_t *ucsra,
volatile uint8_t *ubrrl, volatile uint8_t *ucsrb, const uint8_t u2x, const uint8_t portEnableBits, const uint8_t portTxBits);
volatile uint8_t *ucsra,
volatile uint8_t *ucsrb,
const uint8_t u2x,
const uint8_t portEnableBits,
const uint8_t portTxBits);
// Serial API /// @name Serial API
//@{
virtual void begin(long baud); virtual void begin(long baud);
virtual void begin(long baud, unsigned int rxSpace, unsigned int txSpace);
virtual void end(void); virtual void end(void);
virtual int available(void); virtual int available(void);
virtual int read(void); virtual int read(void);
@ -112,40 +115,90 @@ public:
virtual void flush(void); virtual void flush(void);
virtual void write(uint8_t c); virtual void write(uint8_t c);
using BetterStream::write; using BetterStream::write;
//@}
// public so the interrupt handlers can see it /// 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 { struct Buffer {
volatile uint16_t head, tail; volatile uint16_t head, tail; ///< head and tail pointers
uint16_t mask; uint16_t mask; ///< buffer size mask for pointer wrap
uint8_t *bytes; uint8_t *bytes; ///< pointer to allocated buffer
}; };
private: private:
// register accessors // register accessors
volatile uint8_t *_ubrrh; volatile uint8_t * const _ubrrh;
volatile uint8_t *_ubrrl; volatile uint8_t * const _ubrrl;
volatile uint8_t *_ucsra; volatile uint8_t * const _ucsra;
volatile uint8_t *_ucsrb; volatile uint8_t * const _ucsrb;
// register magic numbers // register magic numbers
uint8_t _portEnableBits; // rx, tx and rx interrupt enables const uint8_t _portEnableBits; ///< rx, tx and rx interrupt enables
uint8_t _portTxBits; // tx data and completion interrupt enables const uint8_t _portTxBits; ///< tx data and completion interrupt enables
uint8_t _u2x; const uint8_t _u2x;
// ring buffers // ring buffers
Buffer *_rxBuffer; Buffer * const _rxBuffer;
Buffer *_txBuffer; Buffer * const _txBuffer;
bool _open; bool _open;
/// 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); 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); 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 // Used by the per-port interrupt vectors
extern FastSerial::Buffer __FastSerial__rxBuffer[]; extern FastSerial::Buffer __FastSerial__rxBuffer[];
extern FastSerial::Buffer __FastSerial__txBuffer[]; 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) \ #define FastSerialHandler(_PORT, _RXVECTOR, _TXVECTOR, _UDR, _UCSRB, _TXBITS) \
ISR(_RXVECTOR, ISR_BLOCK) \ ISR(_RXVECTOR, ISR_BLOCK) \
{ \ { \
@ -215,9 +268,9 @@ struct hack
# endif # endif
#endif #endif
// ///
// Macro defining a FastSerial port instance. /// Macro defining a FastSerial port instance.
// ///
#define FastSerialPort(_name, _num) \ #define FastSerialPort(_name, _num) \
FastSerial _name(_num, \ FastSerial _name(_num, \
&UBRR##_num##H, \ &UBRR##_num##H, \
@ -234,14 +287,14 @@ struct hack
UCSR##_num##B, \ UCSR##_num##B, \
_BV(UDRIE##_num)) _BV(UDRIE##_num))
// ///
// Compatibility macros for previous FastSerial versions. /// Compatibility macros for previous FastSerial versions.
// ///
// Note that these are not conditionally defined, as the errors /// Note that these are not conditionally defined, as the errors
// generated when using these macros for a board that does not support /// 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 /// the port are better than the errors generated for a macro that's not
// defined at all. /// defined at all.
// ///
#define FastSerialPort0(_portName) FastSerialPort(_portName, 0) #define FastSerialPort0(_portName) FastSerialPort(_portName, 0)
#define FastSerialPort1(_portName) FastSerialPort(_portName, 1) #define FastSerialPort1(_portName) FastSerialPort(_portName, 1)
#define FastSerialPort2(_portName) FastSerialPort(_portName, 2) #define FastSerialPort2(_portName) FastSerialPort(_portName, 2)