AP_HAL_AVR: UARTDriver impl uses only sized int types

This commit is contained in:
Pat Hickey 2012-12-06 10:55:31 -08:00 committed by Andrew Tridgell
parent 243590bb73
commit 9455d4c297
2 changed files with 22 additions and 22 deletions

View File

@ -44,7 +44,7 @@ AVRUARTDriver::AVRUARTDriver(
} }
/* UARTDriver method implementations */ /* UARTDriver method implementations */
void AVRUARTDriver::begin(long baud, unsigned int rxSpace, unsigned int txSpace) { void AVRUARTDriver::begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) {
uint16_t ubrr; uint16_t ubrr;
bool use_u2x = true; bool use_u2x = true;
bool need_allocate = true; bool need_allocate = true;
@ -71,7 +71,8 @@ void AVRUARTDriver::begin(long baud, unsigned int rxSpace, unsigned int txSpace)
if (need_allocate) { if (need_allocate) {
// allocate buffers // allocate buffers
if (!_allocBuffer(_rxBuffer, rxSpace ? : _default_rx_buffer_size) || !_allocBuffer(_txBuffer, txSpace ? : _default_tx_buffer_size)) { if (!_allocBuffer(_rxBuffer, rxSpace ? : _default_rx_buffer_size)
|| !_allocBuffer(_txBuffer, txSpace ? : _default_tx_buffer_size)) {
end(); end();
return; // couldn't allocate buffers - fatal return; // couldn't allocate buffers - fatal
} }
@ -118,7 +119,7 @@ void AVRUARTDriver::end() {
_open = false; _open = false;
} }
int AVRUARTDriver::available(void) { int16_t AVRUARTDriver::available(void) {
if (!_open) if (!_open)
return (-1); return (-1);
return ((_rxBuffer->head - _rxBuffer->tail) & _rxBuffer->mask); return ((_rxBuffer->head - _rxBuffer->tail) & _rxBuffer->mask);
@ -126,13 +127,13 @@ int AVRUARTDriver::available(void) {
int AVRUARTDriver::txspace(void) { int16_t AVRUARTDriver::txspace(void) {
if (!_open) if (!_open)
return (-1); return (-1);
return ((_txBuffer->mask+1) - ((_txBuffer->head - _txBuffer->tail) & _txBuffer->mask)); return ((_txBuffer->mask+1) - ((_txBuffer->head - _txBuffer->tail) & _txBuffer->mask));
} }
int AVRUARTDriver::read(void) { int16_t AVRUARTDriver::read(void) {
uint8_t c; uint8_t c;
// if the head and tail are equal, the buffer is empty // if the head and tail are equal, the buffer is empty
@ -146,7 +147,7 @@ int AVRUARTDriver::read(void) {
return (c); return (c);
} }
int AVRUARTDriver::peek(void) { int16_t AVRUARTDriver::peek(void) {
// if the head and tail are equal, the buffer is empty // if the head and tail are equal, the buffer is empty
if (!_open || (_rxBuffer->head == _rxBuffer->tail)) if (!_open || (_rxBuffer->head == _rxBuffer->tail))
@ -204,14 +205,12 @@ size_t AVRUARTDriver::write(uint8_t c) {
} }
// Buffer management /////////////////////////////////////////////////////////// // Buffer management ///////////////////////////////////////////////////////////
static inline unsigned int min (unsigned int a, unsigned int b) {
return (a>b)?b:a;
}
bool AVRUARTDriver::_allocBuffer(Buffer *buffer, unsigned int size) bool AVRUARTDriver::_allocBuffer(Buffer *buffer, uint16_t size)
{ {
uint16_t mask; uint16_t mask;
uint8_t shift; uint8_t shift;
// init buffer state // init buffer state
buffer->head = buffer->tail = 0; buffer->head = buffer->tail = 0;
@ -220,6 +219,7 @@ bool AVRUARTDriver::_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.
#define min(a,b) ((a>b)?b:a)
for (shift = 1; (1U << shift) < min(_max_buffer_size, size); shift++) for (shift = 1; (1U << shift) < min(_max_buffer_size, size); shift++)
; ;
mask = (1 << shift) - 1; mask = (1 << shift) - 1;

View File

@ -24,8 +24,8 @@ public:
const uint8_t portEnableBits, const uint8_t portTxBits); const uint8_t portEnableBits, const uint8_t portTxBits);
/* Implementations of UARTDriver virtual methods */ /* Implementations of UARTDriver virtual methods */
void begin(long b) { begin(b, 0, 0); } void begin(uint32_t b) { begin(b, 0, 0); }
void begin(long b, unsigned int rxS, unsigned int txS); void begin(uint32_t b, uint16_t rxS, uint16_t txS);
void end(); void end();
void flush(); void flush();
bool is_initialized() { return _initialized; } bool is_initialized() { return _initialized; }
@ -47,10 +47,10 @@ public:
__attribute__ ((format(__printf__, 2, 3))); __attribute__ ((format(__printf__, 2, 3)));
/* Implementations of Stream virtual methods */ /* Implementations of Stream virtual methods */
int available(); int16_t available();
int txspace(); int16_t txspace();
int read(); int16_t read();
int peek(); int16_t peek();
/* Implementations of Print virtual methods */ /* Implementations of Print virtual methods */
size_t write(uint8_t c); size_t write(uint8_t c);
@ -96,7 +96,7 @@ private:
/// @param size The desired buffer size. /// @param size The desired buffer size.
/// @returns True if the buffer was allocated successfully. /// @returns True if the buffer was allocated successfully.
/// ///
static bool _allocBuffer(Buffer *buffer, unsigned int size); static bool _allocBuffer(Buffer *buffer, uint16_t size);
/// Frees the allocated buffer in a descriptor /// Frees the allocated buffer in a descriptor
/// ///
@ -105,16 +105,16 @@ private:
static void _freeBuffer(Buffer *buffer); static void _freeBuffer(Buffer *buffer);
/// default receive buffer size /// default receive buffer size
static const unsigned int _default_rx_buffer_size = 128; static const uint16_t _default_rx_buffer_size = 128;
/// default transmit buffer size /// default transmit buffer size
static const unsigned int _default_tx_buffer_size = 16; static const uint16_t _default_tx_buffer_size = 16;
/// maxium tx/rx buffer size /// maxium tx/rx buffer size
/// @note if we could bring the max size down to 256, the mask and head/tail /// @note if we could bring the max size down to 256, the mask and head/tail
/// pointers in the buffer could become uint8_t. /// pointers in the buffer could become uint8_t.
/// ///
static const unsigned int _max_buffer_size = 512; static const uint16_t _max_buffer_size = 512;
}; };
extern AP_HAL_AVR::AVRUARTDriver::Buffer __AVRUARTDriver__rxBuffer[]; extern AP_HAL_AVR::AVRUARTDriver::Buffer __AVRUARTDriver__rxBuffer[];