mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 08:15:30 +03:00
New SPI API supporting DMA
Call targetConfiguration() once before config is loaded and again afterwards in case the config needs to be changed to load from SD card etc Drop SPI clock during binding Remove debug Add per device SPI DMA enable Fix sdioPinConfigure() declaration warning Reduce clock speed during SPI RX initialisation
This commit is contained in:
parent
6d286e25f1
commit
87c8847c13
136 changed files with 3585 additions and 2721 deletions
|
@ -26,6 +26,9 @@
|
|||
|
||||
#ifdef USE_SPI
|
||||
|
||||
// STM32F405 can't DMA to/from FASTRAM (CCM SRAM)
|
||||
#define IS_CCM(p) (((uint32_t)p & 0xffff0000) == 0x10000000)
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "drivers/bus.h"
|
||||
#include "drivers/bus_spi.h"
|
||||
|
@ -33,7 +36,6 @@
|
|||
#include "drivers/exti.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/rcc.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
static SPI_InitTypeDef defaultInit = {
|
||||
.SPI_Mode = SPI_Mode_Master,
|
||||
|
@ -43,160 +45,19 @@ static SPI_InitTypeDef defaultInit = {
|
|||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8,
|
||||
.SPI_CPOL = SPI_CPOL_High,
|
||||
.SPI_CPHA = SPI_CPHA_2Edge
|
||||
};
|
||||
|
||||
void spiInitDevice(SPIDevice device, bool leadingEdge)
|
||||
{
|
||||
spiDevice_t *spi = &(spiDevice[device]);
|
||||
|
||||
if (!spi->dev) {
|
||||
return;
|
||||
}
|
||||
|
||||
#ifndef USE_SPI_TRANSACTION
|
||||
spi->leadingEdge = leadingEdge;
|
||||
#else
|
||||
UNUSED(leadingEdge);
|
||||
#endif
|
||||
|
||||
// Enable SPI clock
|
||||
RCC_ClockCmd(spi->rcc, ENABLE);
|
||||
RCC_ResetCmd(spi->rcc, ENABLE);
|
||||
|
||||
IOInit(IOGetByTag(spi->sck), OWNER_SPI_SCK, RESOURCE_INDEX(device));
|
||||
IOInit(IOGetByTag(spi->miso), OWNER_SPI_MISO, RESOURCE_INDEX(device));
|
||||
IOInit(IOGetByTag(spi->mosi), OWNER_SPI_MOSI, RESOURCE_INDEX(device));
|
||||
|
||||
#if defined(STM32F3) || defined(STM32F4)
|
||||
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af);
|
||||
IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_CFG, spi->af);
|
||||
IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->af);
|
||||
#elif defined(STM32F10X)
|
||||
IOConfigGPIO(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG);
|
||||
IOConfigGPIO(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG);
|
||||
IOConfigGPIO(IOGetByTag(spi->mosi), SPI_IO_AF_MOSI_CFG);
|
||||
#else
|
||||
#error Undefined MCU architecture
|
||||
#endif
|
||||
|
||||
// Init SPI hardware
|
||||
SPI_I2S_DeInit(spi->dev);
|
||||
|
||||
#ifndef USE_SPI_TRANSACTION
|
||||
if (spi->leadingEdge) {
|
||||
defaultInit.SPI_CPOL = SPI_CPOL_Low;
|
||||
defaultInit.SPI_CPHA = SPI_CPHA_1Edge;
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
defaultInit.SPI_CPOL = SPI_CPOL_High;
|
||||
defaultInit.SPI_CPHA = SPI_CPHA_2Edge;
|
||||
}
|
||||
|
||||
#ifdef STM32F303xC
|
||||
// Configure for 8-bit reads.
|
||||
SPI_RxFIFOThresholdConfig(spi->dev, SPI_RxFIFOThreshold_QF);
|
||||
#endif
|
||||
|
||||
SPI_Init(spi->dev, &defaultInit);
|
||||
SPI_Cmd(spi->dev, ENABLE);
|
||||
}
|
||||
|
||||
// return uint8_t value or -1 when failure
|
||||
uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t txByte)
|
||||
{
|
||||
timeUs_t timeoutStartUs = microsISR();
|
||||
|
||||
DISCARD(instance->DR);
|
||||
|
||||
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET) {
|
||||
if (cmpTimeUs(microsISR(), timeoutStartUs) >= SPI_TIMEOUT_US) {
|
||||
return spiTimeoutUserCallback(instance);
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef STM32F303xC
|
||||
SPI_SendData8(instance, txByte);
|
||||
#else
|
||||
SPI_I2S_SendData(instance, txByte);
|
||||
#endif
|
||||
timeoutStartUs = microsISR();
|
||||
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET) {
|
||||
if (cmpTimeUs(microsISR(), timeoutStartUs) >= SPI_TIMEOUT_US) {
|
||||
return spiTimeoutUserCallback(instance);
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef STM32F303xC
|
||||
return ((uint8_t)SPI_ReceiveData8(instance));
|
||||
#else
|
||||
return ((uint8_t)SPI_I2S_ReceiveData(instance));
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* Return true if the bus is currently in the middle of a transmission.
|
||||
*/
|
||||
bool spiIsBusBusy(SPI_TypeDef *instance)
|
||||
{
|
||||
#ifdef STM32F303xC
|
||||
return SPI_GetTransmissionFIFOStatus(instance) != SPI_TransmissionFIFOStatus_Empty || SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_BSY) == SET;
|
||||
#else
|
||||
return SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET || SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_BSY) == SET;
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
bool spiTransfer(SPI_TypeDef *instance, const uint8_t *txData, uint8_t *rxData, int len)
|
||||
{
|
||||
timeUs_t timeoutStartUs;
|
||||
|
||||
uint8_t b;
|
||||
DISCARD(instance->DR);
|
||||
while (len--) {
|
||||
b = txData ? *(txData++) : 0xFF;
|
||||
timeoutStartUs = microsISR();
|
||||
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET) {
|
||||
if (cmpTimeUs(microsISR(), timeoutStartUs) >= SPI_TIMEOUT_US) {
|
||||
return spiTimeoutUserCallback(instance);
|
||||
}
|
||||
}
|
||||
#ifdef STM32F303xC
|
||||
SPI_SendData8(instance, b);
|
||||
#else
|
||||
SPI_I2S_SendData(instance, b);
|
||||
#endif
|
||||
|
||||
timeoutStartUs = microsISR();
|
||||
|
||||
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET) {
|
||||
if (cmpTimeUs(microsISR(), timeoutStartUs) >= SPI_TIMEOUT_US) {
|
||||
return spiTimeoutUserCallback(instance);
|
||||
}
|
||||
}
|
||||
#ifdef STM32F303xC
|
||||
b = SPI_ReceiveData8(instance);
|
||||
#else
|
||||
b = SPI_I2S_ReceiveData(instance);
|
||||
#endif
|
||||
if (rxData) {
|
||||
*(rxData++) = b;
|
||||
}
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static uint16_t spiDivisorToBRbits(SPI_TypeDef *instance, uint16_t divisor)
|
||||
{
|
||||
#if !(defined(STM32F1) || defined(STM32F3))
|
||||
// SPI2 and SPI3 are on APB1/AHB1 which PCLK is half that of APB2/AHB2.
|
||||
|
||||
#if defined(STM32F410xx) || defined(STM32F411xE)
|
||||
UNUSED(instance);
|
||||
#else
|
||||
if (instance == SPI2 || instance == SPI3) {
|
||||
divisor /= 2; // Safe for divisor == 0 or 1
|
||||
}
|
||||
#else
|
||||
UNUSED(instance);
|
||||
#endif
|
||||
|
||||
divisor = constrain(divisor, 2, 256);
|
||||
|
@ -212,61 +73,294 @@ static void spiSetDivisorBRreg(SPI_TypeDef *instance, uint16_t divisor)
|
|||
#undef BR_BITS
|
||||
}
|
||||
|
||||
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
|
||||
|
||||
void spiInitDevice(SPIDevice device)
|
||||
{
|
||||
spiDevice_t *spi = &(spiDevice[device]);
|
||||
|
||||
if (!spi->dev) {
|
||||
return;
|
||||
}
|
||||
|
||||
// Enable SPI clock
|
||||
RCC_ClockCmd(spi->rcc, ENABLE);
|
||||
RCC_ResetCmd(spi->rcc, ENABLE);
|
||||
|
||||
IOInit(IOGetByTag(spi->sck), OWNER_SPI_SCK, RESOURCE_INDEX(device));
|
||||
IOInit(IOGetByTag(spi->miso), OWNER_SPI_MISO, RESOURCE_INDEX(device));
|
||||
IOInit(IOGetByTag(spi->mosi), OWNER_SPI_MOSI, RESOURCE_INDEX(device));
|
||||
|
||||
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG, spi->af);
|
||||
IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG, spi->af);
|
||||
IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->af);
|
||||
|
||||
// Init SPI hardware
|
||||
SPI_I2S_DeInit(spi->dev);
|
||||
|
||||
SPI_I2S_DMACmd(spi->dev, SPI_I2S_DMAReq_Tx | SPI_I2S_DMAReq_Rx, DISABLE);
|
||||
SPI_Init(spi->dev, &defaultInit);
|
||||
SPI_Cmd(spi->dev, ENABLE);
|
||||
}
|
||||
|
||||
void spiInternalResetDescriptors(busDevice_t *bus)
|
||||
{
|
||||
DMA_InitTypeDef *initTx = bus->initTx;
|
||||
DMA_InitTypeDef *initRx = bus->initRx;
|
||||
|
||||
DMA_StructInit(initTx);
|
||||
initTx->DMA_Channel = bus->dmaTxChannel;
|
||||
initTx->DMA_DIR = DMA_DIR_MemoryToPeripheral;
|
||||
initTx->DMA_Mode = DMA_Mode_Normal;
|
||||
initTx->DMA_PeripheralBaseAddr = (uint32_t)&bus->busType_u.spi.instance->DR;
|
||||
initTx->DMA_Priority = DMA_Priority_Low;
|
||||
initTx->DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||
initTx->DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
|
||||
initTx->DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
||||
|
||||
DMA_StructInit(initRx);
|
||||
initRx->DMA_Channel = bus->dmaRxChannel;
|
||||
initRx->DMA_DIR = DMA_DIR_PeripheralToMemory;
|
||||
initRx->DMA_Mode = DMA_Mode_Normal;
|
||||
initRx->DMA_PeripheralBaseAddr = (uint32_t)&bus->busType_u.spi.instance->DR;
|
||||
initRx->DMA_Priority = DMA_Priority_Low;
|
||||
initRx->DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||
initRx->DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
|
||||
}
|
||||
|
||||
void spiInternalResetStream(dmaChannelDescriptor_t *descriptor)
|
||||
{
|
||||
DMA_Stream_TypeDef *streamRegs = (DMA_Stream_TypeDef *)descriptor->ref;
|
||||
|
||||
// Disable the stream
|
||||
streamRegs->CR = 0U;
|
||||
|
||||
// Clear any pending interrupt flags
|
||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF);
|
||||
}
|
||||
|
||||
static bool spiInternalReadWriteBufPolled(SPI_TypeDef *instance, const uint8_t *txData, uint8_t *rxData, int len)
|
||||
{
|
||||
uint8_t b;
|
||||
|
||||
while (len--) {
|
||||
b = txData ? *(txData++) : 0xFF;
|
||||
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET);
|
||||
SPI_I2S_SendData(instance, b);
|
||||
|
||||
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET);
|
||||
b = SPI_I2S_ReceiveData(instance);
|
||||
if (rxData) {
|
||||
*(rxData++) = b;
|
||||
}
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void spiInternalInitStream(const extDevice_t *dev, bool preInit)
|
||||
{
|
||||
static uint8_t dummyTxByte = 0xff;
|
||||
static uint8_t dummyRxByte;
|
||||
busDevice_t *bus = dev->bus;
|
||||
|
||||
volatile busSegment_t *segment = bus->curSegment;
|
||||
|
||||
if (preInit) {
|
||||
// Prepare the init structure for the next segment to reduce inter-segment interval
|
||||
segment++;
|
||||
if(segment->len == 0) {
|
||||
// There's no following segment
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t *txData = segment->txData;
|
||||
uint8_t *rxData = segment->rxData;
|
||||
int len = segment->len;
|
||||
|
||||
DMA_InitTypeDef *initTx = bus->initTx;
|
||||
DMA_InitTypeDef *initRx = bus->initRx;
|
||||
|
||||
if (txData) {
|
||||
initTx->DMA_Memory0BaseAddr = (uint32_t)txData;
|
||||
initTx->DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||
} else {
|
||||
dummyTxByte = 0xff;
|
||||
initTx->DMA_Memory0BaseAddr = (uint32_t)&dummyTxByte;
|
||||
initTx->DMA_MemoryInc = DMA_MemoryInc_Disable;
|
||||
}
|
||||
initTx->DMA_BufferSize = len;
|
||||
|
||||
if (rxData) {
|
||||
initRx->DMA_Memory0BaseAddr = (uint32_t)rxData;
|
||||
initRx->DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||
} else {
|
||||
initRx->DMA_Memory0BaseAddr = (uint32_t)&dummyRxByte;
|
||||
initRx->DMA_MemoryInc = DMA_MemoryInc_Disable;
|
||||
}
|
||||
// If possible use 16 bit memory writes to prevent atomic access issues on gyro data
|
||||
if ((initRx->DMA_Memory0BaseAddr & 0x1) || (len & 0x1))
|
||||
{
|
||||
initRx->DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
||||
} else {
|
||||
initRx->DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
|
||||
}
|
||||
initRx->DMA_BufferSize = len;
|
||||
}
|
||||
|
||||
void spiInternalStartDMA(const extDevice_t *dev)
|
||||
{
|
||||
// Assert Chip Select
|
||||
IOLo(dev->busType_u.spi.csnPin);
|
||||
|
||||
dmaChannelDescriptor_t *dmaTx = dev->bus->dmaTx;
|
||||
dmaChannelDescriptor_t *dmaRx = dev->bus->dmaRx;
|
||||
DMA_Stream_TypeDef *streamRegsTx = (DMA_Stream_TypeDef *)dmaTx->ref;
|
||||
DMA_Stream_TypeDef *streamRegsRx = (DMA_Stream_TypeDef *)dmaRx->ref;
|
||||
|
||||
// Use the correct callback argument
|
||||
dmaRx->userParam = (uint32_t)dev;
|
||||
|
||||
// Clear transfer flags
|
||||
DMA_CLEAR_FLAG(dmaTx, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF);
|
||||
DMA_CLEAR_FLAG(dmaRx, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF);
|
||||
|
||||
// Disable streams to enable update
|
||||
streamRegsTx->CR = 0U;
|
||||
streamRegsRx->CR = 0U;
|
||||
|
||||
/* Use the Rx interrupt as this occurs once the SPI operation is complete whereas the Tx interrupt
|
||||
* occurs earlier when the Tx FIFO is empty, but the SPI operation is still in progress
|
||||
*/
|
||||
DMA_ITConfig(streamRegsRx, DMA_IT_TC, ENABLE);
|
||||
|
||||
// Update streams
|
||||
DMA_Init(streamRegsTx, dev->bus->initTx);
|
||||
DMA_Init(streamRegsRx, dev->bus->initRx);
|
||||
|
||||
/* Note from AN4031
|
||||
*
|
||||
* If the user enables the used peripheral before the corresponding DMA stream, a “FEIF”
|
||||
* (FIFO Error Interrupt Flag) may be set due to the fact the DMA is not ready to provide
|
||||
* the first required data to the peripheral (in case of memory-to-peripheral transfer).
|
||||
*/
|
||||
|
||||
// Enable streams
|
||||
DMA_Cmd(streamRegsTx, ENABLE);
|
||||
DMA_Cmd(streamRegsRx, ENABLE);
|
||||
|
||||
/* Enable the SPI DMA Tx & Rx requests */
|
||||
SPI_I2S_DMACmd(dev->bus->busType_u.spi.instance, SPI_I2S_DMAReq_Tx | SPI_I2S_DMAReq_Rx, ENABLE);
|
||||
}
|
||||
|
||||
|
||||
void spiInternalStopDMA (const extDevice_t *dev)
|
||||
{
|
||||
dmaChannelDescriptor_t *dmaTx = dev->bus->dmaTx;
|
||||
dmaChannelDescriptor_t *dmaRx = dev->bus->dmaRx;
|
||||
DMA_Stream_TypeDef *streamRegsTx = (DMA_Stream_TypeDef *)dmaTx->ref;
|
||||
DMA_Stream_TypeDef *streamRegsRx = (DMA_Stream_TypeDef *)dmaRx->ref;
|
||||
SPI_TypeDef *instance = dev->bus->busType_u.spi.instance;
|
||||
|
||||
// Disable streams
|
||||
streamRegsTx->CR = 0U;
|
||||
streamRegsRx->CR = 0U;
|
||||
|
||||
SPI_I2S_DMACmd(instance, SPI_I2S_DMAReq_Tx | SPI_I2S_DMAReq_Rx, DISABLE);
|
||||
}
|
||||
|
||||
// DMA transfer setup and start
|
||||
void spiSequence(const extDevice_t *dev, busSegment_t *segments)
|
||||
{
|
||||
busDevice_t *bus = dev->bus;
|
||||
SPI_TypeDef *instance = bus->busType_u.spi.instance;
|
||||
bool dmaSafe = dev->useDMA;
|
||||
uint32_t xferLen = 0;
|
||||
uint32_t segmentCount = 0;
|
||||
|
||||
dev->bus->initSegment = true;
|
||||
dev->bus->curSegment = segments;
|
||||
|
||||
SPI_Cmd(instance, DISABLE);
|
||||
spiSetDivisorBRreg(instance, divisor);
|
||||
|
||||
// Switch bus speed
|
||||
if (dev->busType_u.spi.speed != bus->busType_u.spi.speed) {
|
||||
spiSetDivisorBRreg(bus->busType_u.spi.instance, dev->busType_u.spi.speed);
|
||||
bus->busType_u.spi.speed = dev->busType_u.spi.speed;
|
||||
}
|
||||
|
||||
if (dev->busType_u.spi.leadingEdge != bus->busType_u.spi.leadingEdge) {
|
||||
// Switch SPI clock polarity/phase
|
||||
instance->CR1 &= ~(SPI_CPOL_High | SPI_CPHA_2Edge);
|
||||
|
||||
// Apply setting
|
||||
if (dev->busType_u.spi.leadingEdge) {
|
||||
instance->CR1 |= SPI_CPOL_Low | SPI_CPHA_1Edge;
|
||||
} else
|
||||
{
|
||||
instance->CR1 |= SPI_CPOL_High | SPI_CPHA_2Edge;
|
||||
}
|
||||
bus->busType_u.spi.leadingEdge = dev->busType_u.spi.leadingEdge;
|
||||
}
|
||||
|
||||
SPI_Cmd(instance, ENABLE);
|
||||
}
|
||||
|
||||
#ifdef USE_SPI_TRANSACTION
|
||||
|
||||
void spiBusTransactionInit(busDevice_t *bus, SPIMode_e mode, uint16_t divider)
|
||||
{
|
||||
switch (mode) {
|
||||
case SPI_MODE0_POL_LOW_EDGE_1ST:
|
||||
defaultInit.SPI_CPOL = SPI_CPOL_Low;
|
||||
defaultInit.SPI_CPHA = SPI_CPHA_1Edge;
|
||||
break;
|
||||
case SPI_MODE1_POL_LOW_EDGE_2ND:
|
||||
defaultInit.SPI_CPOL = SPI_CPOL_Low;
|
||||
defaultInit.SPI_CPHA = SPI_CPHA_2Edge;
|
||||
break;
|
||||
case SPI_MODE2_POL_HIGH_EDGE_1ST:
|
||||
defaultInit.SPI_CPOL = SPI_CPOL_High;
|
||||
defaultInit.SPI_CPHA = SPI_CPHA_1Edge;
|
||||
break;
|
||||
case SPI_MODE3_POL_HIGH_EDGE_2ND:
|
||||
defaultInit.SPI_CPOL = SPI_CPOL_High;
|
||||
defaultInit.SPI_CPHA = SPI_CPHA_2Edge;
|
||||
break;
|
||||
// Check that any there are no attempts to DMA to/from CCD SRAM
|
||||
for (busSegment_t *checkSegment = bus->curSegment; checkSegment->len; checkSegment++) {
|
||||
if (((checkSegment->rxData) && IS_CCM(checkSegment->rxData)) ||
|
||||
((checkSegment->txData) && IS_CCM(checkSegment->txData))) {
|
||||
dmaSafe = false;
|
||||
break;
|
||||
}
|
||||
// Note that these counts are only valid if dmaSafe is true
|
||||
segmentCount++;
|
||||
xferLen += checkSegment->len;
|
||||
}
|
||||
// Use DMA if possible
|
||||
if (bus->useDMA && dmaSafe && ((segmentCount > 1) || (xferLen > 8))) {
|
||||
// Intialise the init structures for the first transfer
|
||||
spiInternalInitStream(dev, false);
|
||||
|
||||
// Initialize the SPI instance to setup CR1
|
||||
// Start the transfers
|
||||
spiInternalStartDMA(dev);
|
||||
} else {
|
||||
// Manually work through the segment list performing a transfer for each
|
||||
while (bus->curSegment->len) {
|
||||
// Assert Chip Select
|
||||
IOLo(dev->busType_u.spi.csnPin);
|
||||
|
||||
SPI_Init(bus->busdev_u.spi.instance, &defaultInit);
|
||||
spiSetDivisorBRreg(bus->busdev_u.spi.instance, divider);
|
||||
#ifdef STM32F303xC
|
||||
// Configure for 8-bit reads.
|
||||
SPI_RxFIFOThresholdConfig(bus->busdev_u.spi.instance, SPI_RxFIFOThreshold_QF);
|
||||
#endif
|
||||
spiInternalReadWriteBufPolled(
|
||||
bus->busType_u.spi.instance,
|
||||
bus->curSegment->txData,
|
||||
bus->curSegment->rxData,
|
||||
bus->curSegment->len);
|
||||
|
||||
bus->busdev_u.spi.modeCache = bus->busdev_u.spi.instance->CR1;
|
||||
bus->busdev_u.spi.device = &spiDevice[spiDeviceByInstance(bus->busdev_u.spi.instance)];
|
||||
}
|
||||
if (bus->curSegment->negateCS) {
|
||||
// Negate Chip Select
|
||||
IOHi(dev->busType_u.spi.csnPin);
|
||||
}
|
||||
|
||||
void spiBusTransactionSetup(const busDevice_t *bus)
|
||||
{
|
||||
// We rely on MSTR bit to detect valid modeCache
|
||||
if (bus->curSegment->callback) {
|
||||
switch(bus->curSegment->callback(dev->callbackArg)) {
|
||||
case BUS_BUSY:
|
||||
// Repeat the last DMA segment
|
||||
bus->curSegment--;
|
||||
break;
|
||||
|
||||
if (bus->busdev_u.spi.modeCache && bus->busdev_u.spi.modeCache != bus->busdev_u.spi.device->cr1SoftCopy) {
|
||||
bus->busdev_u.spi.instance->CR1 = bus->busdev_u.spi.modeCache;
|
||||
bus->busdev_u.spi.device->cr1SoftCopy = bus->busdev_u.spi.modeCache;
|
||||
case BUS_ABORT:
|
||||
bus->curSegment = (busSegment_t *)NULL;
|
||||
return;
|
||||
|
||||
// SCK seems to require some time to switch to a new initial level after CR1 is written.
|
||||
// Here we buy some time in addition to the software copy save above.
|
||||
__asm__("nop");
|
||||
case BUS_READY:
|
||||
default:
|
||||
// Advance to the next DMA segment
|
||||
break;
|
||||
}
|
||||
}
|
||||
bus->curSegment++;
|
||||
}
|
||||
|
||||
bus->curSegment = (busSegment_t *)NULL;
|
||||
}
|
||||
}
|
||||
#endif // USE_SPI_TRANSACTION
|
||||
#endif
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue