// -*- 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 // HardwareSerial driver: // // Copyright (c) 2006 Nicholas Zambetti. All right reserved. // // Transmit algorithm inspired by work: // // Code Jose Julio and Jordi Munoz. DIYDrones.com // // This library is free software; you can redistribute it and/or // modify it under the terms of the GNU Lesser General Public // License as published by the Free Software Foundation; either // version 2.1 of the License, or (at your option) any later // version. // // This library is distributed in the hope that it will be // useful, but WITHOUT ANY WARRANTY; without even the implied // warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR // PURPOSE. See the GNU Lesser General Public License for more // details. // // You should have received a copy of the GNU Lesser General // Public License along with this library; if not, write to the // Free Software Foundation, Inc., 51 Franklin St, Fifth Floor, // Boston, MA 02110-1301 USA // // // 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 a few bytes of RAM for every unused port and frees up // the vector for another driver (e.g. MSPIM on USARTs). // #ifndef FastSerial_h #define FastSerial_h // disable the stock Arduino serial driver #ifdef HardwareSerial_h # error Must include FastSerial.h before the Arduino serial driver is defined. #endif #define HardwareSerial_h #include #include #include #include #include "BetterStream.h" /// @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(, ) /// /// is the name of the object that will be created by the /// macro. 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() creates referencing serial port 0 /// FastSerialPort1() creates referencing serial port 1 /// FastSerialPort2() creates referencing serial port 2 /// FastSerialPort3() creates 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. /// /// 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; //@} /// The FastSerial class definition /// class FastSerial: public BetterStream { public: /// 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); /// @name Serial API //@{ virtual void begin(long baud); virtual void end(void); virtual int available(void); virtual int txspace(void); virtual int read(void); virtual int peek(void); virtual void flush(void); virtual void write(uint8_t c); using BetterStream::write; //@} /// 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 }; /// Tell if the serial port has been initialized static bool getInitialized(uint8_t port) { return (1<