mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
HAL_ChibiOS: fix irq clash with unnecessary access to readbuf ring buffer
This commit is contained in:
parent
02696882e9
commit
df4bf7e476
@ -622,6 +622,7 @@ void UARTDriver::_timer_tick(void)
|
||||
}
|
||||
_in_timer = true;
|
||||
|
||||
if (!sdef.dma_rx) {
|
||||
// try to fill the read buffer
|
||||
ByteBuffer::IoVec vec[2];
|
||||
|
||||
@ -633,11 +634,9 @@ void UARTDriver::_timer_tick(void)
|
||||
#ifdef HAVE_USB_SERIAL
|
||||
ret = chnReadTimeout((SerialUSBDriver*)sdef.serial, vec[i].data, vec[i].len, TIME_IMMEDIATE);
|
||||
#endif
|
||||
} else if(!sdef.dma_rx){
|
||||
ret = 0;
|
||||
ret = chnReadTimeout((SerialDriver*)sdef.serial, vec[i].data, vec[i].len, TIME_IMMEDIATE);
|
||||
} else {
|
||||
ret = 0;
|
||||
ret = chnReadTimeout((SerialDriver*)sdef.serial, vec[i].data, vec[i].len, TIME_IMMEDIATE);
|
||||
}
|
||||
if (ret < 0) {
|
||||
break;
|
||||
@ -649,6 +648,7 @@ void UARTDriver::_timer_tick(void)
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (unbuffered_writes) {
|
||||
// now send pending bytes. If we are doing "unbuffered" writes
|
||||
|
Loading…
Reference in New Issue
Block a user