2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
29 // STM32F405 can't DMA to/from FASTRAM (CCM SRAM)
30 #define IS_CCM(p) (((uint32_t)p & 0xffff0000) == 0x10000000)
32 #include "common/maths.h"
33 #include "drivers/bus.h"
34 #include "drivers/bus_spi.h"
35 #include "drivers/bus_spi_impl.h"
36 #include "drivers/exti.h"
37 #include "drivers/io.h"
38 #include "drivers/rcc.h"
40 // Use DMA if possible if this many bytes are to be transferred
41 #define SPI_DMA_THRESHOLD 8
43 static SPI_InitTypeDef defaultInit
= {
44 .SPI_Mode
= SPI_Mode_Master
,
45 .SPI_Direction
= SPI_Direction_2Lines_FullDuplex
,
46 .SPI_DataSize
= SPI_DataSize_8b
,
47 .SPI_NSS
= SPI_NSS_Soft
,
48 .SPI_FirstBit
= SPI_FirstBit_MSB
,
49 .SPI_CRCPolynomial
= 7,
50 .SPI_BaudRatePrescaler
= SPI_BaudRatePrescaler_8
,
51 .SPI_CPOL
= SPI_CPOL_High
,
52 .SPI_CPHA
= SPI_CPHA_2Edge
55 static uint16_t spiDivisorToBRbits(const SPI_TypeDef
*instance
, uint16_t divisor
)
57 // SPI2 and SPI3 are on APB1/AHB1 which PCLK is half that of APB2/AHB2.
58 #if defined(STM32F410xx) || defined(STM32F411xE)
61 if (instance
== SPI2
|| instance
== SPI3
) {
62 divisor
/= 2; // Safe for divisor == 0 or 1
66 divisor
= constrain(divisor
, 2, 256);
68 return (ffs(divisor
) - 2) << 3; // SPI_CR1_BR_Pos
71 static void spiSetDivisorBRreg(SPI_TypeDef
*instance
, uint16_t divisor
)
73 #define BR_BITS ((BIT(5) | BIT(4) | BIT(3)))
74 const uint16_t tempRegister
= (instance
->CR1
& ~BR_BITS
);
75 instance
->CR1
= tempRegister
| spiDivisorToBRbits(instance
, divisor
);
79 void spiInitDevice(SPIDevice device
)
81 spiDevice_t
*spi
= &(spiDevice
[device
]);
88 RCC_ClockCmd(spi
->rcc
, ENABLE
);
89 RCC_ResetCmd(spi
->rcc
, ENABLE
);
91 IOInit(IOGetByTag(spi
->sck
), OWNER_SPI_SCK
, RESOURCE_INDEX(device
));
92 IOInit(IOGetByTag(spi
->miso
), OWNER_SPI_SDI
, RESOURCE_INDEX(device
));
93 IOInit(IOGetByTag(spi
->mosi
), OWNER_SPI_SDO
, RESOURCE_INDEX(device
));
95 IOConfigGPIOAF(IOGetByTag(spi
->sck
), SPI_IO_AF_SCK_CFG
, spi
->af
);
96 IOConfigGPIOAF(IOGetByTag(spi
->miso
), SPI_IO_AF_SDI_CFG
, spi
->af
);
97 IOConfigGPIOAF(IOGetByTag(spi
->mosi
), SPI_IO_AF_CFG
, spi
->af
);
100 SPI_I2S_DeInit(spi
->dev
);
102 SPI_I2S_DMACmd(spi
->dev
, SPI_I2S_DMAReq_Tx
| SPI_I2S_DMAReq_Rx
, DISABLE
);
103 SPI_Init(spi
->dev
, &defaultInit
);
104 SPI_Cmd(spi
->dev
, ENABLE
);
107 void spiInternalResetDescriptors(busDevice_t
*bus
)
109 DMA_InitTypeDef
*initTx
= bus
->initTx
;
111 DMA_StructInit(initTx
);
112 initTx
->DMA_Channel
= bus
->dmaTx
->channel
;
113 initTx
->DMA_DIR
= DMA_DIR_MemoryToPeripheral
;
114 initTx
->DMA_Mode
= DMA_Mode_Normal
;
115 initTx
->DMA_PeripheralBaseAddr
= (uint32_t)&bus
->busType_u
.spi
.instance
->DR
;
116 initTx
->DMA_Priority
= DMA_Priority_Low
;
117 initTx
->DMA_PeripheralInc
= DMA_PeripheralInc_Disable
;
118 initTx
->DMA_PeripheralDataSize
= DMA_PeripheralDataSize_Byte
;
119 initTx
->DMA_MemoryDataSize
= DMA_MemoryDataSize_Byte
;
122 DMA_InitTypeDef
*initRx
= bus
->initRx
;
124 DMA_StructInit(initRx
);
125 initRx
->DMA_Channel
= bus
->dmaRx
->channel
;
126 initRx
->DMA_DIR
= DMA_DIR_PeripheralToMemory
;
127 initRx
->DMA_Mode
= DMA_Mode_Normal
;
128 initRx
->DMA_PeripheralBaseAddr
= (uint32_t)&bus
->busType_u
.spi
.instance
->DR
;
129 initRx
->DMA_Priority
= DMA_Priority_Low
;
130 initRx
->DMA_PeripheralInc
= DMA_PeripheralInc_Disable
;
131 initRx
->DMA_PeripheralDataSize
= DMA_PeripheralDataSize_Byte
;
135 void spiInternalResetStream(dmaChannelDescriptor_t
*descriptor
)
137 DMA_Stream_TypeDef
*streamRegs
= (DMA_Stream_TypeDef
*)descriptor
->ref
;
139 // Disable the stream
142 // Clear any pending interrupt flags
143 DMA_CLEAR_FLAG(descriptor
, DMA_IT_HTIF
| DMA_IT_TEIF
| DMA_IT_TCIF
);
146 static bool spiInternalReadWriteBufPolled(SPI_TypeDef
*instance
, const uint8_t *txData
, uint8_t *rxData
, int len
)
151 b
= txData
? *(txData
++) : 0xFF;
152 while (SPI_I2S_GetFlagStatus(instance
, SPI_I2S_FLAG_TXE
) == RESET
);
153 SPI_I2S_SendData(instance
, b
);
155 while (SPI_I2S_GetFlagStatus(instance
, SPI_I2S_FLAG_RXNE
) == RESET
);
156 b
= SPI_I2S_ReceiveData(instance
);
165 void spiInternalInitStream(const extDevice_t
*dev
, bool preInit
)
167 STATIC_DMA_DATA_AUTO
uint8_t dummyTxByte
= 0xff;
168 STATIC_DMA_DATA_AUTO
uint8_t dummyRxByte
;
169 busDevice_t
*bus
= dev
->bus
;
171 volatile busSegment_t
*segment
= bus
->curSegment
;
174 // Prepare the init structure for the next segment to reduce inter-segment interval
176 if(segment
->len
== 0) {
177 // There's no following segment
182 int len
= segment
->len
;
184 uint8_t *txData
= segment
->u
.buffers
.txData
;
185 DMA_InitTypeDef
*initTx
= bus
->initTx
;
188 initTx
->DMA_Memory0BaseAddr
= (uint32_t)txData
;
189 initTx
->DMA_MemoryInc
= DMA_MemoryInc_Enable
;
192 initTx
->DMA_Memory0BaseAddr
= (uint32_t)&dummyTxByte
;
193 initTx
->DMA_MemoryInc
= DMA_MemoryInc_Disable
;
195 initTx
->DMA_BufferSize
= len
;
197 if (dev
->bus
->dmaRx
) {
198 uint8_t *rxData
= segment
->u
.buffers
.rxData
;
199 DMA_InitTypeDef
*initRx
= bus
->initRx
;
202 initRx
->DMA_Memory0BaseAddr
= (uint32_t)rxData
;
203 initRx
->DMA_MemoryInc
= DMA_MemoryInc_Enable
;
205 initRx
->DMA_Memory0BaseAddr
= (uint32_t)&dummyRxByte
;
206 initRx
->DMA_MemoryInc
= DMA_MemoryInc_Disable
;
208 // If possible use 16 bit memory writes to prevent atomic access issues on gyro data
209 if ((initRx
->DMA_Memory0BaseAddr
& 0x1) || (len
& 0x1)) {
210 initRx
->DMA_MemoryDataSize
= DMA_MemoryDataSize_Byte
;
212 initRx
->DMA_MemoryDataSize
= DMA_MemoryDataSize_HalfWord
;
214 initRx
->DMA_BufferSize
= len
;
218 void spiInternalStartDMA(const extDevice_t
*dev
)
220 dmaChannelDescriptor_t
*dmaTx
= dev
->bus
->dmaTx
;
221 dmaChannelDescriptor_t
*dmaRx
= dev
->bus
->dmaRx
;
222 DMA_Stream_TypeDef
*streamRegsTx
= (DMA_Stream_TypeDef
*)dmaTx
->ref
;
224 DMA_Stream_TypeDef
*streamRegsRx
= (DMA_Stream_TypeDef
*)dmaRx
->ref
;
226 // Use the correct callback argument
227 dmaRx
->userParam
= (uint32_t)dev
;
229 // Clear transfer flags
230 DMA_CLEAR_FLAG(dmaTx
, DMA_IT_HTIF
| DMA_IT_TEIF
| DMA_IT_TCIF
);
231 DMA_CLEAR_FLAG(dmaRx
, DMA_IT_HTIF
| DMA_IT_TEIF
| DMA_IT_TCIF
);
233 // Disable streams to enable update
234 streamRegsTx
->CR
= 0U;
235 streamRegsRx
->CR
= 0U;
237 /* Use the Rx interrupt as this occurs once the SPI operation is complete whereas the Tx interrupt
238 * occurs earlier when the Tx FIFO is empty, but the SPI operation is still in progress
240 DMA_ITConfig(streamRegsRx
, DMA_IT_TC
, ENABLE
);
243 DMA_Init(streamRegsTx
, dev
->bus
->initTx
);
244 DMA_Init(streamRegsRx
, dev
->bus
->initRx
);
248 * If the user enables the used peripheral before the corresponding DMA stream, a “FEIF”
249 * (FIFO Error Interrupt Flag) may be set due to the fact the DMA is not ready to provide
250 * the first required data to the peripheral (in case of memory-to-peripheral transfer).
254 DMA_Cmd(streamRegsTx
, ENABLE
);
255 DMA_Cmd(streamRegsRx
, ENABLE
);
257 /* Enable the SPI DMA Tx & Rx requests */
258 SPI_I2S_DMACmd(dev
->bus
->busType_u
.spi
.instance
, SPI_I2S_DMAReq_Tx
| SPI_I2S_DMAReq_Rx
, ENABLE
);
260 // Use the correct callback argument
261 dmaTx
->userParam
= (uint32_t)dev
;
263 // Clear transfer flags
264 DMA_CLEAR_FLAG(dmaTx
, DMA_IT_HTIF
| DMA_IT_TEIF
| DMA_IT_TCIF
);
266 // Disable stream to enable update
267 streamRegsTx
->CR
= 0U;
269 DMA_ITConfig(streamRegsTx
, DMA_IT_TC
, ENABLE
);
272 DMA_Init(streamRegsTx
, dev
->bus
->initTx
);
276 * If the user enables the used peripheral before the corresponding DMA stream, a “FEIF”
277 * (FIFO Error Interrupt Flag) may be set due to the fact the DMA is not ready to provide
278 * the first required data to the peripheral (in case of memory-to-peripheral transfer).
282 DMA_Cmd(streamRegsTx
, ENABLE
);
284 /* Enable the SPI DMA Tx request */
285 SPI_I2S_DMACmd(dev
->bus
->busType_u
.spi
.instance
, SPI_I2S_DMAReq_Tx
, ENABLE
);
289 void spiInternalStopDMA (const extDevice_t
*dev
)
291 dmaChannelDescriptor_t
*dmaTx
= dev
->bus
->dmaTx
;
292 dmaChannelDescriptor_t
*dmaRx
= dev
->bus
->dmaRx
;
293 SPI_TypeDef
*instance
= dev
->bus
->busType_u
.spi
.instance
;
294 DMA_Stream_TypeDef
*streamRegsTx
= (DMA_Stream_TypeDef
*)dmaTx
->ref
;
297 DMA_Stream_TypeDef
*streamRegsRx
= (DMA_Stream_TypeDef
*)dmaRx
->ref
;
300 streamRegsTx
->CR
= 0U;
301 streamRegsRx
->CR
= 0U;
303 SPI_I2S_DMACmd(instance
, SPI_I2S_DMAReq_Tx
| SPI_I2S_DMAReq_Rx
, DISABLE
);
305 // Ensure the current transmission is complete
306 while (SPI_I2S_GetFlagStatus(instance
, SPI_I2S_FLAG_BSY
));
308 // Drain the RX buffer
309 while (SPI_I2S_GetFlagStatus(instance
, SPI_I2S_FLAG_RXNE
)) {
314 streamRegsTx
->CR
= 0U;
316 SPI_I2S_DMACmd(instance
, SPI_I2S_DMAReq_Tx
, DISABLE
);
320 // DMA transfer setup and start
321 void spiSequenceStart(const extDevice_t
*dev
)
323 busDevice_t
*bus
= dev
->bus
;
324 SPI_TypeDef
*instance
= bus
->busType_u
.spi
.instance
;
325 bool dmaSafe
= dev
->useDMA
;
326 uint32_t xferLen
= 0;
327 uint32_t segmentCount
= 0;
329 dev
->bus
->initSegment
= true;
331 SPI_Cmd(instance
, DISABLE
);
334 if (dev
->busType_u
.spi
.speed
!= bus
->busType_u
.spi
.speed
) {
335 spiSetDivisorBRreg(bus
->busType_u
.spi
.instance
, dev
->busType_u
.spi
.speed
);
336 bus
->busType_u
.spi
.speed
= dev
->busType_u
.spi
.speed
;
339 if (dev
->busType_u
.spi
.leadingEdge
!= bus
->busType_u
.spi
.leadingEdge
) {
340 // Switch SPI clock polarity/phase
341 instance
->CR1
&= ~(SPI_CPOL_High
| SPI_CPHA_2Edge
);
344 if (dev
->busType_u
.spi
.leadingEdge
) {
345 instance
->CR1
|= SPI_CPOL_Low
| SPI_CPHA_1Edge
;
348 instance
->CR1
|= SPI_CPOL_High
| SPI_CPHA_2Edge
;
350 bus
->busType_u
.spi
.leadingEdge
= dev
->busType_u
.spi
.leadingEdge
;
353 SPI_Cmd(instance
, ENABLE
);
355 // Check that any there are no attempts to DMA to/from CCD SRAM
356 for (busSegment_t
*checkSegment
= (busSegment_t
*)bus
->curSegment
; checkSegment
->len
; checkSegment
++) {
357 // Check there is no receive data as only transmit DMA is available
358 if (((checkSegment
->u
.buffers
.rxData
) && (IS_CCM(checkSegment
->u
.buffers
.rxData
) || (bus
->dmaRx
== (dmaChannelDescriptor_t
*)NULL
))) ||
359 ((checkSegment
->u
.buffers
.txData
) && IS_CCM(checkSegment
->u
.buffers
.txData
))) {
363 // Note that these counts are only valid if dmaSafe is true
365 xferLen
+= checkSegment
->len
;
367 // Use DMA if possible
368 // If there are more than one segments, or a single segment with negateCS negated in the list terminator then force DMA irrespective of length
369 if (bus
->useDMA
&& dmaSafe
&& ((segmentCount
> 1) ||
370 (xferLen
>= SPI_DMA_THRESHOLD
) ||
371 !bus
->curSegment
[segmentCount
].negateCS
)) {
372 // Intialise the init structures for the first transfer
373 spiInternalInitStream(dev
, false);
375 // Assert Chip Select
376 IOLo(dev
->busType_u
.spi
.csnPin
);
378 // Start the transfers
379 spiInternalStartDMA(dev
);
381 busSegment_t
*lastSegment
= NULL
;
382 bool segmentComplete
;
384 // Manually work through the segment list performing a transfer for each
385 while (bus
->curSegment
->len
) {
386 if (!lastSegment
|| lastSegment
->negateCS
) {
387 // Assert Chip Select if necessary - it's costly so only do so if necessary
388 IOLo(dev
->busType_u
.spi
.csnPin
);
391 spiInternalReadWriteBufPolled(
392 bus
->busType_u
.spi
.instance
,
393 bus
->curSegment
->u
.buffers
.txData
,
394 bus
->curSegment
->u
.buffers
.rxData
,
395 bus
->curSegment
->len
);
397 if (bus
->curSegment
->negateCS
) {
398 // Negate Chip Select
399 IOHi(dev
->busType_u
.spi
.csnPin
);
402 segmentComplete
= true;
403 if (bus
->curSegment
->callback
) {
404 switch(bus
->curSegment
->callback(dev
->callbackArg
)) {
406 // Repeat the last DMA segment
407 segmentComplete
= false;
411 bus
->curSegment
= (busSegment_t
*)BUS_SPI_FREE
;
412 segmentComplete
= false;
417 // Advance to the next DMA segment
421 if (segmentComplete
) {
422 lastSegment
= (busSegment_t
*)bus
->curSegment
;
427 // If a following transaction has been linked, start it
428 if (bus
->curSegment
->u
.link
.dev
) {
429 busSegment_t
*endSegment
= (busSegment_t
*)bus
->curSegment
;
430 const extDevice_t
*nextDev
= endSegment
->u
.link
.dev
;
431 busSegment_t
*nextSegments
= (busSegment_t
*)endSegment
->u
.link
.segments
;
432 bus
->curSegment
= nextSegments
;
433 endSegment
->u
.link
.dev
= NULL
;
434 endSegment
->u
.link
.segments
= NULL
;
435 spiSequenceStart(nextDev
);
437 // The end of the segment list has been reached, so mark transactions as complete
438 bus
->curSegment
= (busSegment_t
*)BUS_SPI_FREE
;