Omit the ::write method, as Print already implements it.

Fix a critical bug in the TX output buffer handling.



git-svn-id: https://arducopter.googlecode.com/svn/trunk@403 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
DrZiplok@gmail.com 2010-09-06 09:01:20 +00:00
parent 46c203e36c
commit 6b6637bd06
2 changed files with 3 additions and 11 deletions

View File

@ -198,9 +198,9 @@ FastSerial::write(uint8_t c)
uint8_t i;
// wait for room in the tx buffer
do {
i = (_txBuffer.head + 1) % RX_BUFFER_SIZE;
} while (i == _txBuffer.tail);
i = (_txBuffer.head + 1) % TX_BUFFER_SIZE;
while (i == _txBuffer.tail)
;
// add byte to the buffer
_txBuffer.bytes[_txBuffer.head] = c;
@ -210,13 +210,6 @@ FastSerial::write(uint8_t c)
*_ucsrb |= _portTxBits;
}
void
FastSerial::write(const uint8_t *buffer, int count)
{
while (count--)
write(*buffer++);
}
// STDIO emulation /////////////////////////////////////////////////////////////
int

View File

@ -104,7 +104,6 @@ public:
int read(void);
void flush(void);
void write(uint8_t c);
void write(const uint8_t *buffer, int count);
using Stream::write;
// stdio extensions