mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-12 02:48:28 -04:00
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:
parent
5c7b99fe33
commit
6ff11ea1fd
@ -99,7 +99,7 @@ void FastSerial::begin(long baud)
|
|||||||
void FastSerial::begin(long baud, unsigned int rxSpace, unsigned int txSpace)
|
void FastSerial::begin(long baud, unsigned int rxSpace, unsigned int txSpace)
|
||||||
{
|
{
|
||||||
uint16_t ubrr;
|
uint16_t ubrr;
|
||||||
bool use_u2x = false;
|
bool use_u2x = true;
|
||||||
int ureg, u2;
|
int ureg, u2;
|
||||||
long breg, b2, dreg, d2;
|
long breg, b2, dreg, d2;
|
||||||
|
|
||||||
@ -115,33 +115,18 @@ void FastSerial::begin(long baud, unsigned int rxSpace, unsigned int txSpace)
|
|||||||
}
|
}
|
||||||
_open = true;
|
_open = true;
|
||||||
|
|
||||||
// U2X mode is needed for bitrates higher than (F_CPU / 16)
|
#if F_CPU == 16000000UL
|
||||||
if (baud > F_CPU / 16) {
|
// hardcoded exception for compatibility with the bootloader shipped
|
||||||
use_u2x = true;
|
// with the Duemilanove and previous boards and the firmware on the 8U2
|
||||||
ubrr = F_CPU / (8 * baud) - 1;
|
// on the Uno and Mega 2560.
|
||||||
|
if (baud == 57600)
|
||||||
|
use_u2x = false;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (use_u2x) {
|
||||||
|
ubrr = (F_CPU / 4 / baud - 1) / 2;
|
||||||
} else {
|
} else {
|
||||||
// Determine whether u2x mode would give a closer
|
ubrr = (F_CPU / 8 / baud - 1) / 2;
|
||||||
// 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;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
*_ucsra = use_u2x ? _BV(_u2x) : 0;
|
*_ucsra = use_u2x ? _BV(_u2x) : 0;
|
||||||
|
Loading…
Reference in New Issue
Block a user