From 9455d4c297b68c0c6708563e65a8ded2057962d5 Mon Sep 17 00:00:00 2001 From: Pat Hickey Date: Thu, 6 Dec 2012 10:55:31 -0800 Subject: [PATCH] AP_HAL_AVR: UARTDriver impl uses only sized int types --- libraries/AP_HAL_AVR/UARTDriver.cpp | 24 ++++++++++++------------ libraries/AP_HAL_AVR/UARTDriver.h | 20 ++++++++++---------- 2 files changed, 22 insertions(+), 22 deletions(-) diff --git a/libraries/AP_HAL_AVR/UARTDriver.cpp b/libraries/AP_HAL_AVR/UARTDriver.cpp index afb92ff61e..c72160bb76 100644 --- a/libraries/AP_HAL_AVR/UARTDriver.cpp +++ b/libraries/AP_HAL_AVR/UARTDriver.cpp @@ -44,7 +44,7 @@ AVRUARTDriver::AVRUARTDriver( } /* 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; bool use_u2x = true; bool need_allocate = true; @@ -71,7 +71,8 @@ void AVRUARTDriver::begin(long baud, unsigned int rxSpace, unsigned int txSpace) if (need_allocate) { // 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(); return; // couldn't allocate buffers - fatal } @@ -118,7 +119,7 @@ void AVRUARTDriver::end() { _open = false; } -int AVRUARTDriver::available(void) { +int16_t AVRUARTDriver::available(void) { if (!_open) return (-1); 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) return (-1); return ((_txBuffer->mask+1) - ((_txBuffer->head - _txBuffer->tail) & _txBuffer->mask)); } -int AVRUARTDriver::read(void) { +int16_t AVRUARTDriver::read(void) { uint8_t c; // if the head and tail are equal, the buffer is empty @@ -146,7 +147,7 @@ int AVRUARTDriver::read(void) { return (c); } -int AVRUARTDriver::peek(void) { +int16_t AVRUARTDriver::peek(void) { // if the head and tail are equal, the buffer is empty if (!_open || (_rxBuffer->head == _rxBuffer->tail)) @@ -204,14 +205,12 @@ size_t AVRUARTDriver::write(uint8_t c) { } // 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; - uint8_t shift; + uint16_t mask; + uint8_t shift; // init buffer state 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 // would seem to make sense, but it uses a 256(!) byte table. // 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++) ; mask = (1 << shift) - 1; diff --git a/libraries/AP_HAL_AVR/UARTDriver.h b/libraries/AP_HAL_AVR/UARTDriver.h index f2b21a1085..5808c5af76 100644 --- a/libraries/AP_HAL_AVR/UARTDriver.h +++ b/libraries/AP_HAL_AVR/UARTDriver.h @@ -24,8 +24,8 @@ public: const uint8_t portEnableBits, const uint8_t portTxBits); /* Implementations of UARTDriver virtual methods */ - void begin(long b) { begin(b, 0, 0); } - void begin(long b, unsigned int rxS, unsigned int txS); + void begin(uint32_t b) { begin(b, 0, 0); } + void begin(uint32_t b, uint16_t rxS, uint16_t txS); void end(); void flush(); bool is_initialized() { return _initialized; } @@ -47,10 +47,10 @@ public: __attribute__ ((format(__printf__, 2, 3))); /* Implementations of Stream virtual methods */ - int available(); - int txspace(); - int read(); - int peek(); + int16_t available(); + int16_t txspace(); + int16_t read(); + int16_t peek(); /* Implementations of Print virtual methods */ size_t write(uint8_t c); @@ -96,7 +96,7 @@ private: /// @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, uint16_t size); /// Frees the allocated buffer in a descriptor /// @@ -105,16 +105,16 @@ private: static void _freeBuffer(Buffer *buffer); /// 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 - static const unsigned int _default_tx_buffer_size = 16; + static const uint16_t _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; + static const uint16_t _max_buffer_size = 512; }; extern AP_HAL_AVR::AVRUARTDriver::Buffer __AVRUARTDriver__rxBuffer[];