AP_HAL_ChibiOS: support is_busy() on WSPI device

This commit is contained in:
Andy Piper 2022-08-31 15:25:33 +01:00 committed by Andrew Tridgell
parent ac8a94e655
commit 93e1859ba6
2 changed files with 10 additions and 0 deletions

View File

@ -85,6 +85,15 @@ WSPIDesc WSPIDeviceManager::device_table[] = { HAL_WSPI_DEVICE_LIST };
#endif
#endif
bool WSPIDevice::is_busy()
{
#if HAL_USE_OCTOSPI
return (wspi_devices[device_desc.bus].driver->ospi->SR & OCTOSPI_SR_BUSY) != 0U;
#else
return (wspi_devices[device_desc.bus].driver->qspi->SR & QUADSPI_SR_BUSY) != 0U;
#endif
}
bool WSPIDevice::transfer(const uint8_t *send, uint32_t send_len,
uint8_t *recv, uint32_t recv_len)
{

View File

@ -111,6 +111,7 @@ public:
#endif
}
bool is_busy() override;
bool acquire_bus(bool acquire);
// Enters Memory mapped or eXecution In Place or 0-4-4 mode