From 34411809d3a90cd1d37873c9f2f386c267083709 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 30 Mar 2023 12:43:02 +0100 Subject: [PATCH] AP_HAL_ChibiOS: revert to ChibiOS SPI driver model v1 --- libraries/AP_HAL_ChibiOS/SPIDevice.cpp | 22 ++++++++++------------ 1 file changed, 10 insertions(+), 12 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/SPIDevice.cpp b/libraries/AP_HAL_ChibiOS/SPIDevice.cpp index 2367f3de36..9b0dd2c3c3 100644 --- a/libraries/AP_HAL_ChibiOS/SPIDevice.cpp +++ b/libraries/AP_HAL_ChibiOS/SPIDevice.cpp @@ -205,7 +205,7 @@ bool SPIDevice::do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len) // expect this timeout to trigger unless there is a severe MCU // error const uint32_t timeout_us = 20000U + len * 32U; - msg_t msg = osalThreadSuspendTimeoutS(&spi_devices[device_desc.bus].driver->sync_transfer, TIME_US2I(timeout_us)); + msg_t msg = osalThreadSuspendTimeoutS(&spi_devices[device_desc.bus].driver->thread, TIME_US2I(timeout_us)); osalSysUnlock(); if (msg == MSG_TIMEOUT) { ret = false; @@ -233,7 +233,7 @@ bool SPIDevice::clock_pulse(uint32_t n) acquire_bus(true, true); osalSysLock(); spiStartIgnoreI(spi_devices[device_desc.bus].driver, n); - msg = osalThreadSuspendTimeoutS(&spi_devices[device_desc.bus].driver->sync_transfer, TIME_US2I(timeout_us)); + msg = osalThreadSuspendTimeoutS(&spi_devices[device_desc.bus].driver->thread, TIME_US2I(timeout_us)); osalSysUnlock(); if (msg == MSG_TIMEOUT) { spiAbort(spi_devices[device_desc.bus].driver); @@ -246,7 +246,7 @@ bool SPIDevice::clock_pulse(uint32_t n) } osalSysLock(); spiStartIgnoreI(spi_devices[device_desc.bus].driver, n); - msg = osalThreadSuspendTimeoutS(&spi_devices[device_desc.bus].driver->sync_transfer, TIME_US2I(timeout_us)); + msg = osalThreadSuspendTimeoutS(&spi_devices[device_desc.bus].driver->thread, TIME_US2I(timeout_us)); osalSysUnlock(); if (msg == MSG_TIMEOUT) { spiAbort(spi_devices[device_desc.bus].driver); @@ -365,18 +365,16 @@ bool SPIDevice::acquire_bus(bool set, bool skip_cs) spiAcquireBus(spi_devices[device_desc.bus].driver); /* Acquire ownership of the bus. */ bus.spicfg.ssport = PAL_PORT(device_desc.pal_line); bus.spicfg.sspad = PAL_PAD(device_desc.pal_line); - bus.spicfg.data_cb = nullptr; - bus.spicfg.error_cb = nullptr; - bus.spicfg.slave = false; + bus.spicfg.end_cb = nullptr; #if defined(STM32H7) bus.spicfg.cfg1 = freq_flag; bus.spicfg.cfg2 = device_desc.mode; - if (bus.spicfg.txsource == nullptr) { - bus.spicfg.txsource = (uint32_t *)malloc_dma(4); - memset(bus.spicfg.txsource, 0xFF, 4); + if (bus.spicfg.dummytx == nullptr) { + bus.spicfg.dummytx = (uint32_t *)malloc_dma(4); + memset(bus.spicfg.dummytx, 0xFF, 4); } - if (bus.spicfg.rxsink == nullptr) { - bus.spicfg.rxsink = (uint32_t *)malloc_dma(4); + if (bus.spicfg.dummyrx == nullptr) { + bus.spicfg.dummyrx = (uint32_t *)malloc_dma(4); } #else bus.spicfg.cr1 = (uint16_t)(freq_flag | device_desc.mode); @@ -502,7 +500,7 @@ void SPIDevice::test_clock_freq(void) uint32_t t0 = AP_HAL::micros(); spiStartExchange(spi_devices[i].driver, len, buf1, buf2); chSysLock(); - msg_t msg = osalThreadSuspendTimeoutS(&spi_devices[i].driver->sync_transfer, chTimeMS2I(100)); + msg_t msg = osalThreadSuspendTimeoutS(&spi_devices[i].driver->thread, chTimeMS2I(100)); chSysUnlock(); if (msg == MSG_TIMEOUT) { spiAbort(spi_devices[i].driver);