mirror of https://github.com/ArduPilot/ardupilot
Stop trying to be so clever in the tx interrupt handler. We may race with the code stuffing bytes into the ring such that we consume the last byte and empty the ring before they set the UDRE interrupt.
If that happens since we weren't checking the ring for emptiness we would loop and spit out the whole ring again. It's cheaper in terms of interrupt latency to just check the ring at interrupt time than it is to futz with ATOMIC_BLOCKs in the ::write code. git-svn-id: https://arducopter.googlecode.com/svn/trunk@535 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
6d31545b8d
commit
9db013e648
|
@ -168,14 +168,17 @@ ISR(_RXVECTOR, ISR_BLOCK) \
|
|||
} \
|
||||
ISR(_TXVECTOR, ISR_BLOCK) \
|
||||
{ \
|
||||
/* if we have taken an interrupt we are ready to transmit the next byte */ \
|
||||
_UDR = __FastSerial__txBuffer[_PORT].bytes[__FastSerial__txBuffer[_PORT].tail]; \
|
||||
/* increment the tail */ \
|
||||
__FastSerial__txBuffer[_PORT].tail = \
|
||||
(__FastSerial__txBuffer[_PORT].tail + 1) & __FastSerial__txBuffer[_PORT].mask; \
|
||||
/* if there are no more bytes to send, disable the interrupt */ \
|
||||
if (__FastSerial__txBuffer[_PORT].head == __FastSerial__txBuffer[_PORT].tail) \
|
||||
_UCSRB &= ~_TXBITS; \
|
||||
/* if there is another character to send */ \
|
||||
if (__FastSerial__txBuffer[_PORT].tail != __FastSerial__txBuffer[_PORT].head) { \
|
||||
_UDR = __FastSerial__txBuffer[_PORT].bytes[__FastSerial__txBuffer[_PORT].tail]; \
|
||||
/* increment the tail */ \
|
||||
__FastSerial__txBuffer[_PORT].tail = \
|
||||
(__FastSerial__txBuffer[_PORT].tail + 1) & __FastSerial__txBuffer[_PORT].mask; \
|
||||
} else { \
|
||||
/* there are no more bytes to send, disable the interrupt */ \
|
||||
if (__FastSerial__txBuffer[_PORT].head == __FastSerial__txBuffer[_PORT].tail) \
|
||||
_UCSRB &= ~_TXBITS; \
|
||||
} \
|
||||
} \
|
||||
struct hack
|
||||
|
||||
|
|
Loading…
Reference in New Issue