mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_ChibiOS: support is_busy() on WSPI device
This commit is contained in:
parent
ac8a94e655
commit
93e1859ba6
@ -85,6 +85,15 @@ WSPIDesc WSPIDeviceManager::device_table[] = { HAL_WSPI_DEVICE_LIST };
|
|||||||
#endif
|
#endif
|
||||||
#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,
|
bool WSPIDevice::transfer(const uint8_t *send, uint32_t send_len,
|
||||||
uint8_t *recv, uint32_t recv_len)
|
uint8_t *recv, uint32_t recv_len)
|
||||||
{
|
{
|
||||||
|
@ -111,6 +111,7 @@ public:
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool is_busy() override;
|
||||||
bool acquire_bus(bool acquire);
|
bool acquire_bus(bool acquire);
|
||||||
|
|
||||||
// Enters Memory mapped or eXecution In Place or 0-4-4 mode
|
// Enters Memory mapped or eXecution In Place or 0-4-4 mode
|
||||||
|
Loading…
Reference in New Issue
Block a user