Browse Source

HAL_ChibiOS: suppress SPI timeout error for expected delay

zr-v5.1
Andrew Tridgell 5 years ago
parent
commit
cf7c2b1475
  1. 4
      libraries/AP_HAL_ChibiOS/SPIDevice.cpp

4
libraries/AP_HAL_ChibiOS/SPIDevice.cpp

@ -207,7 +207,9 @@ bool SPIDevice::do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len) @@ -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…
Cancel
Save