Skip to content

Commit

Permalink
UARTDriver: fix panic when using simulated latency
Browse files Browse the repository at this point in the history
This would sometimes happen when initiating a connection when using
high simulated latency values when the queue would suddenly flush
to the buffer.
  • Loading branch information
robertlong13 committed May 19, 2024
1 parent 04fe12c commit a619a9e
Showing 1 changed file with 3 additions and 1 deletion.
4 changes: 3 additions & 1 deletion libraries/AP_HAL_SITL/UARTDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -268,7 +268,9 @@ void UARTDriver::_flush(void)
size_t UARTDriver::_write(const uint8_t *buffer, size_t size)
{
const auto _txspace = txspace();
if (_txspace < size) {
if (_txspace < size && latencyQueueWrite.empty()) {
// If we're using a latecy queue, we don't actually care about txspace
// at this point, as we're not going to write to the device yet.
size = _txspace;
}
if (size <= 0) {
Expand Down

0 comments on commit a619a9e

Please sign in to comment.