HAL_ChibiOS: fixed sdcard lockup with SPI sdcard

this affects boards that share sdcard on the same bus as another SPI
device. In this case it was a QiotekZealotH743 where logging stopped

this issue is that the SPI hooks for MMC SPI did not do a DMA channel
lock before the SPI device lock. So when the RAMTRON driver on the
QiotekZealotH743 which is on the same SPI2 bus as the sdcard did an
operation we had a lock order violation
This commit is contained in:
Andrew Tridgell 2023-05-13 12:02:26 +10:00
parent ec4b465fea
commit 7e84028a91
2 changed files with 18 additions and 0 deletions

View File

@ -9,6 +9,8 @@ extern "C" {
#if HAL_USE_MMC_SPI == TRUE
void spiStartHook(SPIDriver *spip, const SPIConfig *config);
void spiStopHook(SPIDriver *spip);
void spiAcquireBusHook(SPIDriver *spip);
void spiReleaseBusHook(SPIDriver *spip);
void spiSelectHook(SPIDriver *spip);
void spiUnselectHook(SPIDriver *spip);
void spiIgnoreHook(SPIDriver *spip,size_t n);

View File

@ -213,6 +213,22 @@ void spiStopHook(SPIDriver *spip)
{
}
__RAMFUNC__ void spiAcquireBusHook(SPIDriver *spip)
{
if (sdcard_running) {
ChibiOS::SPIDevice *devptr = static_cast<ChibiOS::SPIDevice*>(device.get());
devptr->acquire_bus(true, true);
}
}
__RAMFUNC__ void spiReleaseBusHook(SPIDriver *spip)
{
if (sdcard_running) {
ChibiOS::SPIDevice *devptr = static_cast<ChibiOS::SPIDevice*>(device.get());
devptr->acquire_bus(false, true);
}
}
__RAMFUNC__ void spiSelectHook(SPIDriver *spip)
{
if (sdcard_running) {