HAL_ChibiOS: suppress SPI timeout error for expected delay
This commit is contained in:
parent
8c49690acf
commit
2215fbd7a4
@ -207,7 +207,9 @@ bool SPIDevice::do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len)
|
||||
osalSysUnlock();
|
||||
if (msg == MSG_TIMEOUT) {
|
||||
ret = false;
|
||||
AP::internalerror().error(AP_InternalError::error_t::spi_fail);
|
||||
if (!hal.scheduler->in_expected_delay()) {
|
||||
AP::internalerror().error(AP_InternalError::error_t::spi_fail);
|
||||
}
|
||||
spiAbort(spi_devices[device_desc.bus].driver);
|
||||
}
|
||||
bus.bouncebuffer_finish(send, recv, len);
|
||||
|
Loading…
Reference in New Issue
Block a user