From ca6d51cddb191b900e10bb444357a1aa4fb68577 Mon Sep 17 00:00:00 2001 From: "DrZiplok@gmail.com" Date: Sun, 17 Oct 2010 06:15:47 +0000 Subject: [PATCH] If ::begin() is called on a port that is already open, preserve the previous buffer settings. This makes it easy to change serial speeds without having to know how the port buffers were set up originally. git-svn-id: https://arducopter.googlecode.com/svn/trunk@672 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- libraries/FastSerial/FastSerial.cpp | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/libraries/FastSerial/FastSerial.cpp b/libraries/FastSerial/FastSerial.cpp index cccd8da3c5..f687525232 100644 --- a/libraries/FastSerial/FastSerial.cpp +++ b/libraries/FastSerial/FastSerial.cpp @@ -116,6 +116,18 @@ FastSerial::FastSerial(const uint8_t portNumber, 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); }