By default mark OSD element as rendered in case it's in the off blink state (#14188...
[betaflight.git] / src / platform / common / stm32 / bus_spi_hw.c
blobb0befd8c34c721c557e48d77aa738ef7061f4804
1 /*
2 * This file is part of Betaflight.
4 * Betaflight is free software. You can redistribute this software
5 * and/or modify this software under the terms of the GNU General
6 * Public License as published by the Free Software Foundation,
7 * either version 3 of the License, or (at your option) any later
8 * version.
10 * Betaflight is distributed in the hope that it will be useful,
11 * but WITHOUT ANY WARRANTY; without even the implied warranty of
12 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
14 * See the GNU General Public License for more details.
16 * You should have received a copy of the GNU General Public
17 * License along with this software.
19 * If not, see <http://www.gnu.org/licenses/>.
22 #include <stdbool.h>
23 #include <stdint.h>
25 #include "platform.h"
27 #include "build/atomic.h"
29 #ifdef USE_SPI
31 #include "drivers/bus.h"
32 #include "drivers/bus_spi.h"
33 #include "drivers/bus_spi_impl.h"
34 #include "drivers/dma_reqmap.h"
35 #include "drivers/motor.h"
36 #include "drivers/nvic.h"
37 #include "pg/bus_spi.h"
39 extern spiDevice_t spiDevice[SPIDEV_COUNT];
40 extern busDevice_t spiBusDevice[SPIDEV_COUNT];
42 // Interrupt handler for SPI receive DMA completion
43 FAST_IRQ_HANDLER static void spiIrqHandler(const extDevice_t *dev)
45 busDevice_t *bus = dev->bus;
46 busSegment_t *nextSegment;
48 if (bus->curSegment->callback) {
49 switch(bus->curSegment->callback(dev->callbackArg)) {
50 case BUS_BUSY:
51 // Repeat the last DMA segment
52 bus->curSegment--;
53 // Reinitialise the cached init values as segment is not progressing
54 spiInternalInitStream(dev, true);
55 break;
57 case BUS_ABORT:
58 // Skip to the end of the segment list
59 nextSegment = (busSegment_t *)bus->curSegment + 1;
60 while (nextSegment->len != 0) {
61 bus->curSegment = nextSegment;
62 nextSegment = (busSegment_t *)bus->curSegment + 1;
64 break;
66 case BUS_READY:
67 default:
68 // Advance to the next DMA segment
69 break;
73 // Advance through the segment list
74 // OK to discard the volatile qualifier here
75 nextSegment = (busSegment_t *)bus->curSegment + 1;
77 if (nextSegment->len == 0) {
78 // If a following transaction has been linked, start it
79 if (nextSegment->u.link.dev) {
80 const extDevice_t *nextDev = nextSegment->u.link.dev;
81 busSegment_t *nextSegments = (busSegment_t *)nextSegment->u.link.segments;
82 // The end of the segment list has been reached
83 bus->curSegment = nextSegments;
84 nextSegment->u.link.dev = NULL;
85 nextSegment->u.link.segments = NULL;
86 spiSequenceStart(nextDev);
87 } else {
88 // The end of the segment list has been reached, so mark transactions as complete
89 bus->curSegment = (busSegment_t *)BUS_SPI_FREE;
91 } else {
92 // Do as much processing as possible before asserting CS to avoid violating minimum high time
93 bool negateCS = bus->curSegment->negateCS;
95 bus->curSegment = nextSegment;
97 // After the completion of the first segment setup the init structure for the subsequent segment
98 if (bus->initSegment) {
99 spiInternalInitStream(dev, false);
100 bus->initSegment = false;
103 if (negateCS) {
104 // Assert Chip Select - it's costly so only do so if necessary
105 IOLo(dev->busType_u.spi.csnPin);
108 // Launch the next transfer
109 spiInternalStartDMA(dev);
111 // Prepare the init structures ready for the next segment to reduce inter-segment time
112 spiInternalInitStream(dev, true);
116 // Interrupt handler for SPI receive DMA completion
117 FAST_IRQ_HANDLER static void spiRxIrqHandler(dmaChannelDescriptor_t* descriptor)
119 const extDevice_t *dev = (const extDevice_t *)descriptor->userParam;
121 if (!dev) {
122 return;
125 busDevice_t *bus = dev->bus;
127 if (bus->curSegment->negateCS) {
128 // Negate Chip Select
129 IOHi(dev->busType_u.spi.csnPin);
132 spiInternalStopDMA(dev);
134 #ifdef __DCACHE_PRESENT
135 #ifdef STM32H7
136 if (bus->curSegment->u.buffers.rxData &&
137 ((bus->curSegment->u.buffers.rxData < &_dmaram_start__) || (bus->curSegment->u.buffers.rxData >= &_dmaram_end__))) {
138 #else
139 if (bus->curSegment->u.buffers.rxData) {
140 #endif
141 // Invalidate the D cache covering the area into which data has been read
142 SCB_InvalidateDCache_by_Addr(
143 (uint32_t *)((uint32_t)bus->curSegment->u.buffers.rxData & ~CACHE_LINE_MASK),
144 (((uint32_t)bus->curSegment->u.buffers.rxData & CACHE_LINE_MASK) +
145 bus->curSegment->len - 1 + CACHE_LINE_SIZE) & ~CACHE_LINE_MASK);
147 #endif // __DCACHE_PRESENT
149 spiIrqHandler(dev);
152 #ifdef USE_TX_IRQ_HANDLER
153 // Interrupt handler for SPI transmit DMA completion
154 FAST_IRQ_HANDLER static void spiTxIrqHandler(dmaChannelDescriptor_t* descriptor)
156 const extDevice_t *dev = (const extDevice_t *)descriptor->userParam;
158 if (!dev) {
159 return;
162 busDevice_t *bus = dev->bus;
164 spiInternalStopDMA(dev);
166 if (bus->curSegment->negateCS) {
167 // Negate Chip Select
168 IOHi(dev->busType_u.spi.csnPin);
171 spiIrqHandler(dev);
173 #endif
175 uint16_t spiCalculateDivider(uint32_t freq)
177 #if defined(STM32F4) || defined(STM32G4) || defined(STM32F7) || defined(APM32F4)
178 uint32_t spiClk = SystemCoreClock / 2;
179 #elif defined(STM32H7)
180 uint32_t spiClk = 100000000;
181 #elif defined(AT32F4)
182 if(freq > 36000000){
183 freq = 36000000;
186 uint32_t spiClk = system_core_clock / 2;
187 #else
188 #error "Base SPI clock not defined for this architecture"
189 #endif
191 uint16_t divisor = 2;
193 spiClk >>= 1;
195 for (; (spiClk > freq) && (divisor < 256); divisor <<= 1, spiClk >>= 1);
197 return divisor;
200 uint32_t spiCalculateClock(uint16_t spiClkDivisor)
202 #if defined(STM32F4) || defined(STM32G4) || defined(STM32F7) || defined(APM32F4)
203 uint32_t spiClk = SystemCoreClock / 2;
204 #elif defined(STM32H7)
205 uint32_t spiClk = 100000000;
206 #elif defined(AT32F4)
207 uint32_t spiClk = system_core_clock / 2;
209 if ((spiClk / spiClkDivisor) > 36000000){
210 return 36000000;
212 #else
213 #error "Base SPI clock not defined for this architecture"
214 #endif
216 return spiClk / spiClkDivisor;
219 void spiInitBusDMA(void)
221 uint32_t device;
222 #if (defined(STM32F4) || defined(APM32F4)) && defined(USE_DSHOT_BITBANG)
223 /* Check https://www.st.com/resource/en/errata_sheet/dm00037591-stm32f405407xx-and-stm32f415417xx-device-limitations-stmicroelectronics.pdf
224 * section 2.1.10 which reports an errata that corruption may occurs on DMA2 if AHB peripherals (eg GPIO ports) are
225 * access concurrently with APB peripherals (eg SPI busses). Bitbang DSHOT uses DMA2 to write to GPIO ports. If this
226 * is enabled, then don't enable DMA on an SPI bus using DMA2
228 const bool dshotBitbangActive = isDshotBitbangActive(&motorConfig()->dev);
229 #endif
231 for (device = 0; device < SPIDEV_COUNT; device++) {
232 busDevice_t *bus = &spiBusDevice[device];
234 if (bus->busType != BUS_TYPE_SPI) {
235 // This bus is not in use
236 continue;
239 dmaIdentifier_e dmaTxIdentifier = DMA_NONE;
240 dmaIdentifier_e dmaRxIdentifier = DMA_NONE;
242 int8_t txDmaopt = spiPinConfig(device)->txDmaopt;
243 uint8_t txDmaoptMin = 0;
244 uint8_t txDmaoptMax = MAX_PERIPHERAL_DMA_OPTIONS - 1;
246 if (txDmaopt != -1) {
247 txDmaoptMin = txDmaopt;
248 txDmaoptMax = txDmaopt;
251 for (uint8_t opt = txDmaoptMin; opt <= txDmaoptMax; opt++) {
252 const dmaChannelSpec_t *dmaTxChannelSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_SPI_SDO, device, opt);
254 if (dmaTxChannelSpec) {
255 dmaTxIdentifier = dmaGetIdentifier(dmaTxChannelSpec->ref);
256 #if (defined(STM32F4) || defined(APM32F4)) && defined(USE_DSHOT_BITBANG)
257 if (dshotBitbangActive && (DMA_DEVICE_NO(dmaTxIdentifier) == 2)) {
258 dmaTxIdentifier = DMA_NONE;
259 break;
261 #endif
262 if (!dmaAllocate(dmaTxIdentifier, OWNER_SPI_SDO, device + 1)) {
263 dmaTxIdentifier = DMA_NONE;
264 continue;
266 bus->dmaTx = dmaGetDescriptorByIdentifier(dmaTxIdentifier);
267 #if defined(STM32F4) || defined(STM32F7) || defined(STM32G4) || defined(STM32H7) || defined(APM32F4)
268 bus->dmaTx->stream = DMA_DEVICE_INDEX(dmaTxIdentifier);
269 bus->dmaTx->channel = dmaTxChannelSpec->channel;
270 #endif
272 dmaEnable(dmaTxIdentifier);
273 #if defined(USE_ATBSP_DRIVER)
274 dmaMuxEnable(dmaTxIdentifier,dmaTxChannelSpec->dmaMuxId);
275 #endif
276 break;
280 int8_t rxDmaopt = spiPinConfig(device)->rxDmaopt;
281 uint8_t rxDmaoptMin = 0;
282 uint8_t rxDmaoptMax = MAX_PERIPHERAL_DMA_OPTIONS - 1;
284 if (rxDmaopt != -1) {
285 rxDmaoptMin = rxDmaopt;
286 rxDmaoptMax = rxDmaopt;
289 for (uint8_t opt = rxDmaoptMin; opt <= rxDmaoptMax; opt++) {
290 const dmaChannelSpec_t *dmaRxChannelSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_SPI_SDI, device, opt);
292 if (dmaRxChannelSpec) {
293 dmaRxIdentifier = dmaGetIdentifier(dmaRxChannelSpec->ref);
294 #if (defined(STM32F4) || defined(APM32F4)) && defined(USE_DSHOT_BITBANG)
295 if (dshotBitbangActive && (DMA_DEVICE_NO(dmaRxIdentifier) == 2)) {
296 dmaRxIdentifier = DMA_NONE;
297 break;
299 #endif
300 if (!dmaAllocate(dmaRxIdentifier, OWNER_SPI_SDI, device + 1)) {
301 dmaRxIdentifier = DMA_NONE;
302 continue;
304 bus->dmaRx = dmaGetDescriptorByIdentifier(dmaRxIdentifier);
305 #if defined(STM32F4) || defined(STM32F7) || defined(STM32G4) || defined(STM32H7) || defined(APM32F4)
306 bus->dmaRx->stream = DMA_DEVICE_INDEX(dmaRxIdentifier);
307 bus->dmaRx->channel = dmaRxChannelSpec->channel;
308 #endif
310 dmaEnable(dmaRxIdentifier);
311 #if defined(USE_ATBSP_DRIVER)
312 dmaMuxEnable(dmaRxIdentifier,dmaRxChannelSpec->dmaMuxId);
313 #endif
314 break;
318 if (dmaTxIdentifier && dmaRxIdentifier) {
319 // Ensure streams are disabled
320 spiInternalResetStream(bus->dmaRx);
321 spiInternalResetStream(bus->dmaTx);
323 spiInternalResetDescriptors(bus);
325 /* Note that this driver may be called both from the normal thread of execution, or from USB interrupt
326 * handlers, so the DMA completion interrupt must be at a higher priority
328 dmaSetHandler(dmaRxIdentifier, spiRxIrqHandler, NVIC_PRIO_SPI_DMA, 0);
330 bus->useDMA = true;
331 #ifdef USE_TX_IRQ_HANDLER
332 } else if (dmaTxIdentifier) {
333 // Transmit on DMA is adequate for OSD so worth having
334 bus->dmaTx = dmaGetDescriptorByIdentifier(dmaTxIdentifier);
335 bus->dmaRx = (dmaChannelDescriptor_t *)NULL;
337 // Ensure streams are disabled
338 spiInternalResetStream(bus->dmaTx);
340 spiInternalResetDescriptors(bus);
342 dmaSetHandler(dmaTxIdentifier, spiTxIrqHandler, NVIC_PRIO_SPI_DMA, 0);
344 bus->useDMA = true;
345 #endif
346 } else {
347 // Disassociate channels from bus
348 bus->dmaRx = (dmaChannelDescriptor_t *)NULL;
349 bus->dmaTx = (dmaChannelDescriptor_t *)NULL;
354 #endif