mirror of https://github.com/ArduPilot/ardupilot
FastSerial: avoid buffer re-allocation on re-open if possible
we commonly re-open serial ports a lot in the AUTO GPS driver
This commit is contained in:
parent
aeaebb21d5
commit
9c1ce9e1c5
|
@ -82,6 +82,7 @@ void FastSerial::begin(long baud, unsigned int rxSpace, unsigned int txSpace)
|
||||||
{
|
{
|
||||||
uint16_t ubrr;
|
uint16_t ubrr;
|
||||||
bool use_u2x = true;
|
bool use_u2x = true;
|
||||||
|
bool need_allocate = true;
|
||||||
|
|
||||||
// if we are currently open...
|
// if we are currently open...
|
||||||
if (_open) {
|
if (_open) {
|
||||||
|
@ -92,15 +93,24 @@ void FastSerial::begin(long baud, unsigned int rxSpace, unsigned int txSpace)
|
||||||
if (0 == txSpace)
|
if (0 == txSpace)
|
||||||
txSpace = _txBuffer->mask + 1;
|
txSpace = _txBuffer->mask + 1;
|
||||||
|
|
||||||
|
if (rxSpace == (_rxBuffer->mask + 1) &&
|
||||||
|
txSpace == (_txBuffer->mask + 1)) {
|
||||||
|
// avoid re-allocating the buffers if possible
|
||||||
|
need_allocate = false;
|
||||||
|
*_ucsrb &= ~(_portEnableBits | _portTxBits);
|
||||||
|
} else {
|
||||||
// close the port in its current configuration, clears _open
|
// close the port in its current configuration, clears _open
|
||||||
end();
|
end();
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (need_allocate) {
|
||||||
// allocate buffers
|
// allocate buffers
|
||||||
if (!_allocBuffer(_rxBuffer, rxSpace ? : _default_rx_buffer_size) || !_allocBuffer(_txBuffer, txSpace ? : _default_tx_buffer_size)) {
|
if (!_allocBuffer(_rxBuffer, rxSpace ? : _default_rx_buffer_size) || !_allocBuffer(_txBuffer, txSpace ? : _default_tx_buffer_size)) {
|
||||||
end();
|
end();
|
||||||
return; // couldn't allocate buffers - fatal
|
return; // couldn't allocate buffers - fatal
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// reset buffer pointers
|
// reset buffer pointers
|
||||||
_txBuffer->head = _txBuffer->tail = 0;
|
_txBuffer->head = _txBuffer->tail = 0;
|
||||||
|
|
Loading…
Reference in New Issue