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
This commit is contained in:
DrZiplok@gmail.com 2010-10-17 06:15:47 +00:00
parent 0a94520682
commit ca6d51cddb
1 changed files with 12 additions and 0 deletions

View File

@ -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);
}