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,31 +622,31 @@ void UARTDriver::_timer_tick(void)
|
|||||||
}
|
}
|
||||||
_in_timer = true;
|
_in_timer = true;
|
||||||
|
|
||||||
// try to fill the read buffer
|
if (!sdef.dma_rx) {
|
||||||
ByteBuffer::IoVec vec[2];
|
// try to fill the read buffer
|
||||||
|
ByteBuffer::IoVec vec[2];
|
||||||
|
|
||||||
const auto n_vec = _readbuf.reserve(vec, _readbuf.space());
|
const auto n_vec = _readbuf.reserve(vec, _readbuf.space());
|
||||||
for (int i = 0; i < n_vec; i++) {
|
for (int i = 0; i < n_vec; i++) {
|
||||||
//Do a non-blocking read
|
//Do a non-blocking read
|
||||||
if (sdef.is_usb) {
|
if (sdef.is_usb) {
|
||||||
ret = 0;
|
ret = 0;
|
||||||
#ifdef HAVE_USB_SERIAL
|
#ifdef HAVE_USB_SERIAL
|
||||||
ret = chnReadTimeout((SerialUSBDriver*)sdef.serial, vec[i].data, vec[i].len, TIME_IMMEDIATE);
|
ret = chnReadTimeout((SerialUSBDriver*)sdef.serial, vec[i].data, vec[i].len, TIME_IMMEDIATE);
|
||||||
#endif
|
#endif
|
||||||
} else if(!sdef.dma_rx){
|
} else {
|
||||||
ret = 0;
|
ret = 0;
|
||||||
ret = chnReadTimeout((SerialDriver*)sdef.serial, vec[i].data, vec[i].len, TIME_IMMEDIATE);
|
ret = chnReadTimeout((SerialDriver*)sdef.serial, vec[i].data, vec[i].len, TIME_IMMEDIATE);
|
||||||
} else {
|
}
|
||||||
ret = 0;
|
if (ret < 0) {
|
||||||
}
|
break;
|
||||||
if (ret < 0) {
|
}
|
||||||
break;
|
_readbuf.commit((unsigned)ret);
|
||||||
}
|
|
||||||
_readbuf.commit((unsigned)ret);
|
/* stop reading as we read less than we asked for */
|
||||||
|
if ((unsigned)ret < vec[i].len) {
|
||||||
/* stop reading as we read less than we asked for */
|
break;
|
||||||
if ((unsigned)ret < vec[i].len) {
|
}
|
||||||
break;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user