Simplify FastSerial::begin baudrate calculations in line with the changes made in Arduino-0022

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1424 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
DrZiplok 2011-01-04 18:41:27 +00:00
parent 5c7b99fe33
commit 6ff11ea1fd

View File

@ -99,7 +99,7 @@ void FastSerial::begin(long baud)
void FastSerial::begin(long baud, unsigned int rxSpace, unsigned int txSpace)
{
uint16_t ubrr;
bool use_u2x = false;
bool use_u2x = true;
int ureg, u2;
long breg, b2, dreg, d2;
@ -115,33 +115,18 @@ void FastSerial::begin(long baud, unsigned int rxSpace, unsigned int txSpace)
}
_open = true;
// U2X mode is needed for bitrates higher than (F_CPU / 16)
if (baud > F_CPU / 16) {
use_u2x = true;
ubrr = F_CPU / (8 * baud) - 1;
#if F_CPU == 16000000UL
// hardcoded exception for compatibility with the bootloader shipped
// with the Duemilanove and previous boards and the firmware on the 8U2
// on the Uno and Mega 2560.
if (baud == 57600)
use_u2x = false;
#endif
if (use_u2x) {
ubrr = (F_CPU / 4 / baud - 1) / 2;
} else {
// Determine whether u2x mode would give a closer
// approximation of the desired speed.
// ubrr for non-2x mode, corresponding baudrate and delta
ureg = F_CPU / 16 / baud - 1;
breg = F_CPU / 16 / (ureg + 1);
dreg = abs(baud - breg);
// ubrr for 2x mode, corresponding bitrate and delta
u2 = F_CPU / 8 / baud - 1;
b2 = F_CPU / 8 / (u2 + 1);
d2 = abs(baud - b2);
// Pick the setting that gives the smallest rate
// error, preferring non-u2x mode if the delta is
// identical.
if (dreg <= d2) {
ubrr = ureg;
} else {
ubrr = u2;
use_u2x = true;
}
ubrr = (F_CPU / 8 / baud - 1) / 2;
}
*_ucsra = use_u2x ? _BV(_u2x) : 0;