mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
HAL_ChibiOS: scale RTS threshold to make software CTS more effective
This commit is contained in:
parent
ebc4ee99a9
commit
34815f9fb0
@ -299,6 +299,7 @@ void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|||||||
_rx_initialised = false;
|
_rx_initialised = false;
|
||||||
_readbuf.set_size_best(rxS);
|
_readbuf.set_size_best(rxS);
|
||||||
}
|
}
|
||||||
|
_rts_threshold = _readbuf.get_size() / 16U;
|
||||||
|
|
||||||
bool clear_buffers = false;
|
bool clear_buffers = false;
|
||||||
if (b != 0) {
|
if (b != 0) {
|
||||||
@ -1414,10 +1415,10 @@ __RAMFUNC__ void UARTDriver::update_rts_line(void)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
uint16_t space = _readbuf.space();
|
uint16_t space = _readbuf.space();
|
||||||
if (_rts_is_active && space < 16) {
|
if (_rts_is_active && space < _rts_threshold) {
|
||||||
_rts_is_active = false;
|
_rts_is_active = false;
|
||||||
palSetLine(arts_line);
|
palSetLine(arts_line);
|
||||||
} else if (!_rts_is_active && space > 32) {
|
} else if (!_rts_is_active && space > _rts_threshold+16) {
|
||||||
_rts_is_active = true;
|
_rts_is_active = true;
|
||||||
palClearLine(arts_line);
|
palClearLine(arts_line);
|
||||||
}
|
}
|
||||||
|
@ -182,6 +182,7 @@ private:
|
|||||||
#endif
|
#endif
|
||||||
ByteBuffer _readbuf{0};
|
ByteBuffer _readbuf{0};
|
||||||
ByteBuffer _writebuf{0};
|
ByteBuffer _writebuf{0};
|
||||||
|
uint32_t _rts_threshold;
|
||||||
HAL_Semaphore _write_mutex;
|
HAL_Semaphore _write_mutex;
|
||||||
#ifndef HAL_UART_NODMA
|
#ifndef HAL_UART_NODMA
|
||||||
const stm32_dma_stream_t* rxdma;
|
const stm32_dma_stream_t* rxdma;
|
||||||
|
Loading…
Reference in New Issue
Block a user