mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: account for TXFIFO when doing flow control detection
This commit is contained in:
parent
d71fb2cb34
commit
5fa50c419d
|
@ -1135,9 +1135,18 @@ void UARTDriver::write_pending_bytes(void)
|
||||||
// remaining queue space
|
// remaining queue space
|
||||||
uint32_t space = qSpaceI(&((SerialDriver*)sdef.serial)->oqueue);
|
uint32_t space = qSpaceI(&((SerialDriver*)sdef.serial)->oqueue);
|
||||||
uint32_t used = SERIAL_BUFFERS_SIZE - space;
|
uint32_t used = SERIAL_BUFFERS_SIZE - space;
|
||||||
|
|
||||||
|
#if !defined(USART_CR1_FIFOEN)
|
||||||
// threshold is 8 for the GCS_Common code to unstick SiK radios, which
|
// threshold is 8 for the GCS_Common code to unstick SiK radios, which
|
||||||
// sends 6 bytes with flow control disabled
|
// sends 6 bytes with flow control disabled
|
||||||
const uint8_t threshold = 8;
|
const uint8_t threshold = 8;
|
||||||
|
#else
|
||||||
|
// account for TX FIFO buffer
|
||||||
|
uint8_t threshold = 12;
|
||||||
|
if (_last_options & OPTION_NOFIFO) {
|
||||||
|
threshold = 8;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
if (_total_written > used && _total_written - used > threshold) {
|
if (_total_written > used && _total_written - used > threshold) {
|
||||||
_flow_control = FLOW_CONTROL_ENABLE;
|
_flow_control = FLOW_CONTROL_ENABLE;
|
||||||
return;
|
return;
|
||||||
|
|
Loading…
Reference in New Issue