mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 06:15:16 +03:00
[H7] Enable SPI with resurrected HAL-based driver from v3.1.7
This commit is contained in:
parent
77ef37bad0
commit
82c978a828
7 changed files with 434 additions and 11 deletions
|
@ -74,6 +74,7 @@ bool spiInit(SPIDevice device)
|
|||
switch (device) {
|
||||
case SPIINVALID:
|
||||
return false;
|
||||
|
||||
case SPIDEV_1:
|
||||
#ifdef USE_SPI_DEVICE_1
|
||||
spiInitDevice(device);
|
||||
|
@ -81,6 +82,7 @@ bool spiInit(SPIDevice device)
|
|||
#else
|
||||
break;
|
||||
#endif
|
||||
|
||||
case SPIDEV_2:
|
||||
#ifdef USE_SPI_DEVICE_2
|
||||
spiInitDevice(device);
|
||||
|
@ -88,6 +90,7 @@ bool spiInit(SPIDevice device)
|
|||
#else
|
||||
break;
|
||||
#endif
|
||||
|
||||
case SPIDEV_3:
|
||||
#if defined(USE_SPI_DEVICE_3) && !defined(STM32F1)
|
||||
spiInitDevice(device);
|
||||
|
@ -95,6 +98,7 @@ bool spiInit(SPIDevice device)
|
|||
#else
|
||||
break;
|
||||
#endif
|
||||
|
||||
case SPIDEV_4:
|
||||
#if defined(USE_SPI_DEVICE_4)
|
||||
spiInitDevice(device);
|
||||
|
@ -102,6 +106,22 @@ bool spiInit(SPIDevice device)
|
|||
#else
|
||||
break;
|
||||
#endif
|
||||
|
||||
case SPIDEV_5:
|
||||
#if defined(USE_SPI_DEVICE_5)
|
||||
spiInitDevice(device);
|
||||
return true;
|
||||
#else
|
||||
break;
|
||||
#endif
|
||||
|
||||
case SPIDEV_6:
|
||||
#if defined(USE_SPI_DEVICE_6)
|
||||
spiInitDevice(device);
|
||||
return true;
|
||||
#else
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
#define SPI_IO_AF_SCK_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_DOWN)
|
||||
#define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP)
|
||||
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
|
||||
#elif defined(STM32F7)
|
||||
#elif defined(STM32F7) || defined(STM32H7)
|
||||
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_NOPULL)
|
||||
#define SPI_IO_AF_SCK_CFG_HIGH IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP)
|
||||
#define SPI_IO_AF_SCK_CFG_LOW IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLDOWN)
|
||||
|
@ -61,6 +61,12 @@ typedef enum {
|
|||
SPI_CLOCK_STANDARD = 16, //06.57500 MHz
|
||||
SPI_CLOCK_FAST = 8, //13.50000 MHz
|
||||
SPI_CLOCK_ULTRAFAST = 2 //54.00000 MHz
|
||||
#elif defined(STM32H7)
|
||||
// spi_ker_ck = 100MHz
|
||||
SPI_CLOCK_SLOW = 128, //00.78125 MHz
|
||||
SPI_CLOCK_STANDARD = 8, //12.00000 MHz
|
||||
SPI_CLOCK_FAST = 4, //25.00000 MHz
|
||||
SPI_CLOCK_ULTRAFAST = 2 //50.00000 MHz
|
||||
#else
|
||||
SPI_CLOCK_SLOW = 128, //00.56250 MHz
|
||||
SPI_CLOCK_STANDARD = 4, //09.00000 MHz
|
||||
|
@ -89,7 +95,9 @@ typedef enum SPIDevice {
|
|||
SPIDEV_1 = 0,
|
||||
SPIDEV_2,
|
||||
SPIDEV_3,
|
||||
SPIDEV_4
|
||||
SPIDEV_4,
|
||||
SPIDEV_5,
|
||||
SPIDEV_6
|
||||
} SPIDevice;
|
||||
|
||||
#if defined(STM32F1)
|
||||
|
@ -98,6 +106,8 @@ typedef enum SPIDevice {
|
|||
#define SPIDEV_COUNT 3
|
||||
#elif defined(STM32F7)
|
||||
#define SPIDEV_COUNT 4
|
||||
#elif defined(STM32H7)
|
||||
#define SPIDEV_COUNT 6
|
||||
#else
|
||||
#define SPIDEV_COUNT 4
|
||||
|
||||
|
|
263
src/main/drivers/bus_spi_hal.c
Normal file
263
src/main/drivers/bus_spi_hal.c
Normal file
|
@ -0,0 +1,263 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
// HAL version resurrected from v3.1.7
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <strings.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_SPI
|
||||
|
||||
#include "bus_spi.h"
|
||||
#include "bus_spi_impl.h"
|
||||
#include "dma.h"
|
||||
#include "io.h"
|
||||
#include "io_impl.h"
|
||||
#include "nvic.h"
|
||||
#include "rcc.h"
|
||||
|
||||
void spiInitDevice(SPIDevice device)
|
||||
{
|
||||
spiDevice_t *spi = &(spiDevice[device]);
|
||||
|
||||
if (!spi->dev) {
|
||||
return;
|
||||
}
|
||||
|
||||
#ifdef SDCARD_SPI_INSTANCE
|
||||
if (spi->dev == SDCARD_SPI_INSTANCE) {
|
||||
spi->leadingEdge = true;
|
||||
}
|
||||
#endif
|
||||
#ifdef RX_SPI_INSTANCE
|
||||
if (spi->dev == RX_SPI_INSTANCE) {
|
||||
spi->leadingEdge = true;
|
||||
}
|
||||
#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)
|
||||
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);
|
||||
#endif
|
||||
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
|
||||
IOConfigGPIOAF(IOGetByTag(spi->sck), spi->leadingEdge ? SPI_IO_AF_SCK_CFG_LOW : SPI_IO_AF_SCK_CFG_HIGH, spi->sckAF);
|
||||
IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG, spi->misoAF);
|
||||
IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->mosiAF);
|
||||
#endif
|
||||
|
||||
#if 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);
|
||||
#endif
|
||||
|
||||
spi->hspi.Instance = spi->dev;
|
||||
// DeInit SPI hardware
|
||||
HAL_SPI_DeInit(&spi->hspi);
|
||||
|
||||
spi->hspi.Init.Mode = SPI_MODE_MASTER;
|
||||
spi->hspi.Init.Direction = SPI_DIRECTION_2LINES;
|
||||
spi->hspi.Init.DataSize = SPI_DATASIZE_8BIT;
|
||||
spi->hspi.Init.NSS = SPI_NSS_SOFT;
|
||||
spi->hspi.Init.FirstBit = SPI_FIRSTBIT_MSB;
|
||||
spi->hspi.Init.CRCPolynomial = 7;
|
||||
spi->hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_256;
|
||||
spi->hspi.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
|
||||
spi->hspi.Init.TIMode = SPI_TIMODE_DISABLED;
|
||||
spi->hspi.Init.FifoThreshold = SPI_FIFO_THRESHOLD_01DATA;
|
||||
spi->hspi.Init.MasterKeepIOState = SPI_MASTER_KEEP_IO_STATE_ENABLE; /* Recommanded setting to avoid glitches */
|
||||
|
||||
if (spi->leadingEdge) {
|
||||
spi->hspi.Init.CLKPolarity = SPI_POLARITY_LOW;
|
||||
spi->hspi.Init.CLKPhase = SPI_PHASE_1EDGE;
|
||||
}
|
||||
else {
|
||||
spi->hspi.Init.CLKPolarity = SPI_POLARITY_HIGH;
|
||||
spi->hspi.Init.CLKPhase = SPI_PHASE_2EDGE;
|
||||
}
|
||||
|
||||
// Init SPI hardware
|
||||
HAL_SPI_Init(&spi->hspi);
|
||||
}
|
||||
|
||||
// return uint8_t value or -1 when failure
|
||||
uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t out)
|
||||
{
|
||||
uint8_t in;
|
||||
|
||||
spiTransfer(instance, &out, &in, 1);
|
||||
return in;
|
||||
}
|
||||
|
||||
/**
|
||||
* Return true if the bus is currently in the middle of a transmission.
|
||||
*/
|
||||
bool spiIsBusBusy(SPI_TypeDef *instance)
|
||||
{
|
||||
SPIDevice device = spiDeviceByInstance(instance);
|
||||
if(spiDevice[device].hspi.State == HAL_SPI_STATE_BUSY)
|
||||
return true;
|
||||
else
|
||||
return false;
|
||||
}
|
||||
|
||||
bool spiTransfer(SPI_TypeDef *instance, const uint8_t *out, uint8_t *in, int len)
|
||||
{
|
||||
SPIDevice device = spiDeviceByInstance(instance);
|
||||
HAL_StatusTypeDef status;
|
||||
|
||||
#define SPI_DEFAULT_TIMEOUT 10
|
||||
|
||||
if (!in) {
|
||||
// Tx only
|
||||
status = HAL_SPI_Transmit(&spiDevice[device].hspi, out, len, SPI_DEFAULT_TIMEOUT);
|
||||
} else if(!out) {
|
||||
// Rx only
|
||||
status = HAL_SPI_Receive(&spiDevice[device].hspi, in, len, SPI_DEFAULT_TIMEOUT);
|
||||
} else {
|
||||
// Tx and Rx
|
||||
status = HAL_SPI_TransmitReceive(&spiDevice[device].hspi, out, in, len, SPI_DEFAULT_TIMEOUT);
|
||||
}
|
||||
|
||||
if(status != HAL_OK) {
|
||||
spiTimeoutUserCallback(instance);
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// Position of Prescaler bits are different from MCU to MCU
|
||||
|
||||
static uint32_t baudRatePrescaler[8] = {
|
||||
SPI_BAUDRATEPRESCALER_2,
|
||||
SPI_BAUDRATEPRESCALER_4,
|
||||
SPI_BAUDRATEPRESCALER_8,
|
||||
SPI_BAUDRATEPRESCALER_16,
|
||||
SPI_BAUDRATEPRESCALER_32,
|
||||
SPI_BAUDRATEPRESCALER_64,
|
||||
SPI_BAUDRATEPRESCALER_128,
|
||||
SPI_BAUDRATEPRESCALER_256,
|
||||
};
|
||||
|
||||
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
|
||||
{
|
||||
SPIDevice device = spiDeviceByInstance(instance);
|
||||
|
||||
HAL_SPI_DeInit(&spiDevice[device].hspi);
|
||||
|
||||
spiDevice_t *spi = &(spiDevice[device]);
|
||||
|
||||
int prescalerIndex = ffs(divisor) - 2; // prescaler begins at "/2"
|
||||
|
||||
if (prescalerIndex < 0 || prescalerIndex >= (int)ARRAYLEN(baudRatePrescaler)) {
|
||||
return;
|
||||
}
|
||||
|
||||
spi->hspi.Init.BaudRatePrescaler = baudRatePrescaler[prescalerIndex];
|
||||
|
||||
HAL_SPI_Init(&spi->hspi);
|
||||
}
|
||||
|
||||
#ifdef USE_DMA
|
||||
DMA_HandleTypeDef* dmaHandleByInstance(SPI_TypeDef *instance)
|
||||
{
|
||||
return &spiDevice[spiDeviceByInstance(instance)].hdma;
|
||||
}
|
||||
|
||||
void SPI1_IRQHandler(void)
|
||||
{
|
||||
HAL_SPI_IRQHandler(&spiDevice[SPIDEV_1].hspi);
|
||||
}
|
||||
|
||||
void SPI2_IRQHandler(void)
|
||||
{
|
||||
HAL_SPI_IRQHandler(&spiDevice[SPIDEV_2].hspi);
|
||||
}
|
||||
|
||||
void SPI3_IRQHandler(void)
|
||||
{
|
||||
HAL_SPI_IRQHandler(&spiDevice[SPIDEV_3].hspi);
|
||||
}
|
||||
|
||||
void SPI4_IRQHandler(void)
|
||||
{
|
||||
HAL_SPI_IRQHandler(&spiDevice[SPIDEV_4].hspi);
|
||||
}
|
||||
|
||||
void dmaSPIIRQHandler(dmaChannelDescriptor_t* descriptor)
|
||||
{
|
||||
SPIDevice device = descriptor->userParam;
|
||||
if (device != SPIINVALID)
|
||||
HAL_DMA_IRQHandler(&spiDevice[device].hdma);
|
||||
}
|
||||
|
||||
DMA_HandleTypeDef* spiSetDMATransmit(DMA_Stream_TypeDef *Stream, uint32_t Channel, SPI_TypeDef *Instance, uint8_t *pData, uint16_t Size)
|
||||
{
|
||||
SPIDevice device = spiDeviceByInstance(Instance);
|
||||
spiDevice_t *spi = &(spiDevice[device]);
|
||||
|
||||
spi->hdma.Instance = Stream;
|
||||
#if !defined(STM32H7)
|
||||
spi->hdma.Init.Channel = Channel;
|
||||
#else
|
||||
UNUSED(Channel);
|
||||
#endif
|
||||
spi->hdma.Init.Direction = DMA_MEMORY_TO_PERIPH;
|
||||
spi->hdma.Init.PeriphInc = DMA_PINC_DISABLE;
|
||||
spi->hdma.Init.MemInc = DMA_MINC_ENABLE;
|
||||
spi->hdma.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
|
||||
spi->hdma.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
|
||||
spi->hdma.Init.Mode = DMA_NORMAL;
|
||||
spi->hdma.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
|
||||
spi->hdma.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
|
||||
spi->hdma.Init.PeriphBurst = DMA_PBURST_SINGLE;
|
||||
spi->hdma.Init.MemBurst = DMA_MBURST_SINGLE;
|
||||
spi->hdma.Init.Priority = DMA_PRIORITY_LOW;
|
||||
|
||||
HAL_DMA_DeInit(&spi->hdma);
|
||||
HAL_DMA_Init(&spi->hdma);
|
||||
|
||||
__HAL_DMA_ENABLE(&spi->hdma);
|
||||
__HAL_SPI_ENABLE(&spi->hspi);
|
||||
|
||||
/* Associate the initialized DMA handle to the spi handle */
|
||||
__HAL_LINKDMA(&spi->hspi, hdmatx, spi->hdma);
|
||||
|
||||
// DMA TX Interrupt
|
||||
dmaSetHandler(spi->dmaIrqHandler, dmaSPIIRQHandler, NVIC_BUILD_PRIORITY(3, 0), (uint32_t)device);
|
||||
|
||||
//HAL_CLEANCACHE(pData,Size);
|
||||
// And Transmit
|
||||
HAL_SPI_Transmit_DMA(&spi->hspi, pData, Size);
|
||||
|
||||
return &spi->hdma;
|
||||
}
|
||||
#endif // USE_DMA
|
||||
#endif
|
|
@ -22,13 +22,17 @@
|
|||
|
||||
#if defined(STM32F1) || defined(STM32F3) || defined(STM32F4)
|
||||
#define MAX_SPI_PIN_SEL 2
|
||||
#else
|
||||
#elif defined(STM32F7)
|
||||
#define MAX_SPI_PIN_SEL 4
|
||||
#elif defined(STM32H7)
|
||||
#define MAX_SPI_PIN_SEL 5
|
||||
#else
|
||||
#error Unknown MCU family
|
||||
#endif
|
||||
|
||||
typedef struct spiPinDef_s {
|
||||
ioTag_t pin;
|
||||
#ifdef STM32F7
|
||||
#if defined(STM32F7) || defined(STM32H7)
|
||||
uint8_t af;
|
||||
#endif
|
||||
} spiPinDef_t;
|
||||
|
@ -43,7 +47,7 @@ typedef struct spiHardware_s {
|
|||
uint8_t af;
|
||||
#endif
|
||||
rccPeriphTag_t rcc;
|
||||
#if defined(USE_HAL_DRIVER)
|
||||
#if defined(USE_DMA) && defined(USE_HAL_DRIVER)
|
||||
uint8_t dmaIrqHandler;
|
||||
#endif
|
||||
} spiHardware_t;
|
||||
|
@ -55,7 +59,7 @@ typedef struct SPIDevice_s {
|
|||
ioTag_t sck;
|
||||
ioTag_t miso;
|
||||
ioTag_t mosi;
|
||||
#ifdef STM32F7
|
||||
#if defined(STM32F7) || defined(STM32H7)
|
||||
uint8_t sckAF;
|
||||
uint8_t misoAF;
|
||||
uint8_t mosiAF;
|
||||
|
@ -67,9 +71,11 @@ typedef struct SPIDevice_s {
|
|||
bool leadingEdge;
|
||||
#if defined(USE_HAL_DRIVER)
|
||||
SPI_HandleTypeDef hspi;
|
||||
#ifdef USE_DMA
|
||||
DMA_HandleTypeDef hdma;
|
||||
uint8_t dmaIrqHandler;
|
||||
#endif
|
||||
#endif
|
||||
#ifdef USE_SPI_TRANSACTION
|
||||
uint16_t cr1SoftCopy; // Copy of active CR1 value for this SPI instance
|
||||
#endif
|
||||
|
|
|
@ -279,6 +279,105 @@ const spiHardware_t spiHardware[] = {
|
|||
.dmaIrqHandler = DMA2_ST1_HANDLER,
|
||||
},
|
||||
#endif
|
||||
#ifdef STM32H7
|
||||
{
|
||||
.device = SPIDEV_1,
|
||||
.reg = SPI1,
|
||||
.sckPins = {
|
||||
{ DEFIO_TAG_E(PA5), GPIO_AF5_SPI1 },
|
||||
{ DEFIO_TAG_E(PB3), GPIO_AF5_SPI1 },
|
||||
},
|
||||
.misoPins = {
|
||||
{ DEFIO_TAG_E(PA6), GPIO_AF5_SPI1 },
|
||||
{ DEFIO_TAG_E(PB4), GPIO_AF5_SPI1 },
|
||||
},
|
||||
.mosiPins = {
|
||||
{ DEFIO_TAG_E(PA7), GPIO_AF5_SPI1 },
|
||||
{ DEFIO_TAG_E(PB5), GPIO_AF5_SPI1 },
|
||||
},
|
||||
.rcc = RCC_APB2(SPI1),
|
||||
//.dmaIrqHandler = DMA2_ST3_HANDLER,
|
||||
},
|
||||
{
|
||||
.device = SPIDEV_2,
|
||||
.reg = SPI2,
|
||||
.sckPins = {
|
||||
{ DEFIO_TAG_E(PA9), GPIO_AF5_SPI2 },
|
||||
{ DEFIO_TAG_E(PA12), GPIO_AF5_SPI2 },
|
||||
{ DEFIO_TAG_E(PB10), GPIO_AF5_SPI2 },
|
||||
{ DEFIO_TAG_E(PB13), GPIO_AF5_SPI2 },
|
||||
{ DEFIO_TAG_E(PD3), GPIO_AF5_SPI2 },
|
||||
},
|
||||
.misoPins = {
|
||||
{ DEFIO_TAG_E(PB14), GPIO_AF5_SPI2 },
|
||||
{ DEFIO_TAG_E(PC2), GPIO_AF5_SPI2 },
|
||||
},
|
||||
.mosiPins = {
|
||||
{ DEFIO_TAG_E(PB15), GPIO_AF5_SPI2 },
|
||||
{ DEFIO_TAG_E(PC1), GPIO_AF5_SPI2 },
|
||||
{ DEFIO_TAG_E(PC3), GPIO_AF5_SPI2 },
|
||||
},
|
||||
.rcc = RCC_APB1L(SPI2),
|
||||
//.dmaIrqHandler = DMA1_ST4_HANDLER,
|
||||
},
|
||||
{
|
||||
.device = SPIDEV_3,
|
||||
.reg = SPI3,
|
||||
.sckPins = {
|
||||
{ DEFIO_TAG_E(PB3), GPIO_AF6_SPI3 },
|
||||
{ DEFIO_TAG_E(PC10), GPIO_AF6_SPI3 },
|
||||
},
|
||||
.misoPins = {
|
||||
{ DEFIO_TAG_E(PB4), GPIO_AF6_SPI3 },
|
||||
{ DEFIO_TAG_E(PC11), GPIO_AF6_SPI3 },
|
||||
},
|
||||
.mosiPins = {
|
||||
{ DEFIO_TAG_E(PB2), GPIO_AF7_SPI3 },
|
||||
{ DEFIO_TAG_E(PB5), GPIO_AF7_SPI3 },
|
||||
{ DEFIO_TAG_E(PC12), GPIO_AF6_SPI3 },
|
||||
{ DEFIO_TAG_E(PD6), GPIO_AF5_SPI3 },
|
||||
},
|
||||
.rcc = RCC_APB1L(SPI3),
|
||||
//.dmaIrqHandler = DMA1_ST7_HANDLER,
|
||||
},
|
||||
{
|
||||
.device = SPIDEV_4,
|
||||
.reg = SPI4,
|
||||
.sckPins = {
|
||||
{ DEFIO_TAG_E(PE2), GPIO_AF5_SPI4 },
|
||||
{ DEFIO_TAG_E(PE12), GPIO_AF5_SPI4 },
|
||||
},
|
||||
.misoPins = {
|
||||
{ DEFIO_TAG_E(PE5), GPIO_AF5_SPI4 },
|
||||
{ DEFIO_TAG_E(PE13), GPIO_AF5_SPI4 },
|
||||
},
|
||||
.mosiPins = {
|
||||
{ DEFIO_TAG_E(PE6), GPIO_AF5_SPI4 },
|
||||
{ DEFIO_TAG_E(PE14), GPIO_AF5_SPI4 },
|
||||
},
|
||||
.rcc = RCC_APB2(SPI4),
|
||||
//.dmaIrqHandler = DMA2_ST1_HANDLER,
|
||||
},
|
||||
// SPI5 is not available for LPQFP-100 or 144 package
|
||||
{
|
||||
.device = SPIDEV_6,
|
||||
.reg = SPI6,
|
||||
.sckPins = {
|
||||
{ DEFIO_TAG_E(PA5), GPIO_AF8_SPI6 },
|
||||
{ DEFIO_TAG_E(PB3), GPIO_AF8_SPI6 },
|
||||
},
|
||||
.misoPins = {
|
||||
{ DEFIO_TAG_E(PA6), GPIO_AF8_SPI6 },
|
||||
{ DEFIO_TAG_E(PB4), GPIO_AF8_SPI6 },
|
||||
},
|
||||
.mosiPins = {
|
||||
{ DEFIO_TAG_E(PA7), GPIO_AF8_SPI6 },
|
||||
{ DEFIO_TAG_E(PB5), GPIO_AF8_SPI6 },
|
||||
},
|
||||
.rcc = RCC_APB4(SPI6),
|
||||
//.dmaIrqHandler = DMA2_ST1_HANDLER,
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
||||
void spiPinConfigure(const spiPinConfig_t *pConfig)
|
||||
|
@ -296,19 +395,19 @@ void spiPinConfigure(const spiPinConfig_t *pConfig)
|
|||
for (int pindex = 0 ; pindex < MAX_SPI_PIN_SEL ; pindex++) {
|
||||
if (pConfig[device].ioTagSck == hw->sckPins[pindex].pin) {
|
||||
pDev->sck = hw->sckPins[pindex].pin;
|
||||
#ifdef STM32F7
|
||||
#if defined(STM32F7) || defined(STM32H7)
|
||||
pDev->sckAF = hw->sckPins[pindex].af;
|
||||
#endif
|
||||
}
|
||||
if (pConfig[device].ioTagMiso == hw->misoPins[pindex].pin) {
|
||||
pDev->miso = hw->misoPins[pindex].pin;
|
||||
#ifdef STM32F7
|
||||
#if defined(STM32F7) || defined(STM32H7)
|
||||
pDev->misoAF = hw->misoPins[pindex].af;
|
||||
#endif
|
||||
}
|
||||
if (pConfig[device].ioTagMosi == hw->mosiPins[pindex].pin) {
|
||||
pDev->mosi = hw->mosiPins[pindex].pin;
|
||||
#ifdef STM32F7
|
||||
#if defined(STM32F7) || defined(STM32H7)
|
||||
pDev->mosiAF = hw->mosiPins[pindex].af;
|
||||
#endif
|
||||
}
|
||||
|
@ -316,12 +415,12 @@ void spiPinConfigure(const spiPinConfig_t *pConfig)
|
|||
|
||||
if (pDev->sck && pDev->miso && pDev->mosi) {
|
||||
pDev->dev = hw->reg;
|
||||
#ifndef STM32F7
|
||||
#if !(defined(STM32F7) || defined(STM32H7))
|
||||
pDev->af = hw->af;
|
||||
#endif
|
||||
pDev->rcc = hw->rcc;
|
||||
pDev->leadingEdge = false; // XXX Should be part of transfer context
|
||||
#ifdef USE_HAL_DRIVER
|
||||
#if defined(USE_DMA) && defined(USE_HAL_DRIVER)
|
||||
pDev->dmaIrqHandler = hw->dmaIrqHandler;
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -460,6 +460,12 @@ void init(void)
|
|||
#ifdef USE_SPI_DEVICE_4
|
||||
spiInit(SPIDEV_4);
|
||||
#endif
|
||||
#ifdef USE_SPI_DEVICE_5
|
||||
spiInit(SPIDEV_5);
|
||||
#endif
|
||||
#ifdef USE_SPI_DEVICE_6
|
||||
spiInit(SPIDEV_6);
|
||||
#endif
|
||||
#endif // USE_SPI
|
||||
|
||||
#ifdef USE_USB_MSC
|
||||
|
|
|
@ -240,6 +240,25 @@
|
|||
#define SPI3_MISO_PIN PB4
|
||||
#define SPI3_MOSI_PIN PB5
|
||||
#endif
|
||||
|
||||
#ifndef SPI4_SCK_PIN
|
||||
#define SPI4_SCK_PIN NONE
|
||||
#define SPI4_MISO_PIN NONE
|
||||
#define SPI4_MOSI_PIN NONE
|
||||
#endif
|
||||
|
||||
#ifndef SPI5_SCK_PIN
|
||||
#define SPI5_SCK_PIN NONE
|
||||
#define SPI5_MISO_PIN NONE
|
||||
#define SPI5_MOSI_PIN NONE
|
||||
#endif
|
||||
|
||||
#ifndef SPI6_SCK_PIN
|
||||
#define SPI6_SCK_PIN NONE
|
||||
#define SPI6_MISO_PIN NONE
|
||||
#define SPI6_MOSI_PIN NONE
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
// Extracted from rx/rx.c and rx/rx.h
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue