Move all F7 to use LL

This commit is contained in:
blckmn 2017-07-30 12:10:46 +10:00
parent f3e2470907
commit 834289e456
10 changed files with 87 additions and 544 deletions

View File

@ -61,8 +61,6 @@ EXCLUDES = stm32f7xx_hal_can.c \
stm32f7xx_ll_adc.c \ stm32f7xx_ll_adc.c \
stm32f7xx_ll_crc.c \ stm32f7xx_ll_crc.c \
stm32f7xx_ll_dac.c \ stm32f7xx_ll_dac.c \
stm32f7xx_ll_dma.c \
stm32f7xx_ll_dma2d.c \
stm32f7xx_ll_exti.c \ stm32f7xx_ll_exti.c \
stm32f7xx_ll_fmc.c \ stm32f7xx_ll_fmc.c \
stm32f7xx_ll_i2c.c \ stm32f7xx_ll_i2c.c \
@ -151,7 +149,6 @@ MCU_COMMON_SRC = \
drivers/bus_i2c_hal.c \ drivers/bus_i2c_hal.c \
drivers/dma_stm32f7xx.c \ drivers/dma_stm32f7xx.c \
drivers/light_ws2811strip_hal.c \ drivers/light_ws2811strip_hal.c \
drivers/bus_spi_hal.c \
drivers/bus_spi_ll.c \ drivers/bus_spi_ll.c \
drivers/pwm_output_dshot_hal.c \ drivers/pwm_output_dshot_hal.c \
drivers/timer_hal.c \ drivers/timer_hal.c \

View File

@ -23,10 +23,10 @@
#include "drivers/rcc_types.h" #include "drivers/rcc_types.h"
#if defined(STM32F4) || defined(STM32F3) #if defined(STM32F4) || defined(STM32F3)
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL) #define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
#define SPI_IO_AF_SCK_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_DOWN) #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_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) #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)
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_NOPULL) #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_HIGH IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP)
@ -34,10 +34,10 @@
#define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP) #define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP)
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_NOPULL) #define SPI_IO_CS_CFG IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_NOPULL)
#elif defined(STM32F1) #elif defined(STM32F1)
#define SPI_IO_AF_SCK_CFG IO_CONFIG(GPIO_Mode_AF_PP, GPIO_Speed_50MHz) #define SPI_IO_AF_SCK_CFG IO_CONFIG(GPIO_Mode_AF_PP, GPIO_Speed_50MHz)
#define SPI_IO_AF_MOSI_CFG IO_CONFIG(GPIO_Mode_AF_PP, GPIO_Speed_50MHz) #define SPI_IO_AF_MOSI_CFG IO_CONFIG(GPIO_Mode_AF_PP, GPIO_Speed_50MHz)
#define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_Mode_IN_FLOATING, GPIO_Speed_50MHz) #define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_Mode_IN_FLOATING, GPIO_Speed_50MHz)
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_Out_PP, GPIO_Speed_50MHz) #define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_Out_PP, GPIO_Speed_50MHz)
#endif #endif
/* /*
@ -101,11 +101,6 @@ SPI_TypeDef *spiInstanceByDevice(SPIDevice device);
bool spiBusTransfer(const busDevice_t *bus, const uint8_t *txData, uint8_t *rxData, int length); bool spiBusTransfer(const busDevice_t *bus, const uint8_t *txData, uint8_t *rxData, int length);
#if defined(USE_HAL_DRIVER)
SPI_HandleTypeDef* spiHandleByInstance(SPI_TypeDef *instance);
DMA_HandleTypeDef* spiSetDMATransmit(DMA_Stream_TypeDef *Stream, uint32_t Channel, SPI_TypeDef *Instance, const uint8_t *pData, uint16_t Size);
#endif
bool spiBusWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data); bool spiBusWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data);
bool spiBusReadRegisterBuffer(const busDevice_t *bus, uint8_t reg, uint8_t *data, uint8_t length); bool spiBusReadRegisterBuffer(const busDevice_t *bus, uint8_t reg, uint8_t *data, uint8_t length);
uint8_t spiBusReadRegister(const busDevice_t *bus, uint8_t reg); uint8_t spiBusReadRegister(const busDevice_t *bus, uint8_t reg);

View File

@ -1,449 +0,0 @@
/*
* 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/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <platform.h>
#if defined(USE_SPI) && !defined(USE_LOWLEVEL_DRIVER)
#include "common/utils.h"
#include "drivers/bus.h"
#include "drivers/bus_spi.h"
#include "drivers/bus_spi_impl.h"
#include "drivers/dma.h"
#include "drivers/io.h"
#include "drivers/nvic.h"
#include "drivers/rcc.h"
spiDevice_t spiDevice[SPIDEV_COUNT];
#ifndef SPI2_SCK_PIN
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#endif
#ifndef SPI3_SCK_PIN
#define SPI3_NSS_PIN PA15
#define SPI3_SCK_PIN PB3
#define SPI3_MISO_PIN PB4
#define SPI3_MOSI_PIN PB5
#endif
#ifndef SPI4_SCK_PIN
#define SPI4_NSS_PIN PA15
#define SPI4_SCK_PIN PB3
#define SPI4_MISO_PIN PB4
#define SPI4_MOSI_PIN PB5
#endif
#ifndef SPI1_NSS_PIN
#define SPI1_NSS_PIN NONE
#endif
#ifndef SPI2_NSS_PIN
#define SPI2_NSS_PIN NONE
#endif
#ifndef SPI3_NSS_PIN
#define SPI3_NSS_PIN NONE
#endif
#ifndef SPI4_NSS_PIN
#define SPI4_NSS_PIN NONE
#endif
#define SPI_DEFAULT_TIMEOUT 10
SPIDevice spiDeviceByInstance(SPI_TypeDef *instance)
{
#ifdef USE_SPI_DEVICE_1
if (instance == SPI1)
return SPIDEV_1;
#endif
#ifdef USE_SPI_DEVICE_2
if (instance == SPI2)
return SPIDEV_2;
#endif
#ifdef USE_SPI_DEVICE_3
if (instance == SPI3)
return SPIDEV_3;
#endif
#ifdef USE_SPI_DEVICE_4
if (instance == SPI4)
return SPIDEV_4;
#endif
return SPIINVALID;
}
SPI_HandleTypeDef* spiHandleByInstance(SPI_TypeDef *instance)
{
return &spiDevice[spiDeviceByInstance(instance)].hspi;
}
SPI_TypeDef *spiInstanceByDevice(SPIDevice device)
{
if (device >= SPIDEV_COUNT) {
return NULL;
}
return spiDevice[device].dev;
}
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 spiInitDevice(SPIDevice device)
{
spiDevice_t *spi = &(spiDevice[device]);
#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
#ifdef MPU6500_SPI_INSTANCE
if (spi->dev == MPU6500_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(STM32F7)
if (spi->leadingEdge == true)
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG_LOW, spi->sckAF);
else
IOConfigGPIOAF(IOGetByTag(spi->sck), 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(STM32F3) || defined(STM32F4)
if (spi->leadingEdge == true)
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG_LOW, spi->af);
else
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG_HIGH, spi->af);
IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG, spi->af);
IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->af);
#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
spiDevice[device].hspi.Instance = spi->dev;
// Init SPI hardware
HAL_SPI_DeInit(&spiDevice[device].hspi);
spiDevice[device].hspi.Init.Mode = SPI_MODE_MASTER;
spiDevice[device].hspi.Init.Direction = SPI_DIRECTION_2LINES;
spiDevice[device].hspi.Init.DataSize = SPI_DATASIZE_8BIT;
spiDevice[device].hspi.Init.NSS = SPI_NSS_SOFT;
spiDevice[device].hspi.Init.FirstBit = SPI_FIRSTBIT_MSB;
spiDevice[device].hspi.Init.CRCPolynomial = 7;
spiDevice[device].hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_256;
spiDevice[device].hspi.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
spiDevice[device].hspi.Init.TIMode = SPI_TIMODE_DISABLED;
if (spi->leadingEdge) {
spiDevice[device].hspi.Init.CLKPolarity = SPI_POLARITY_LOW;
spiDevice[device].hspi.Init.CLKPhase = SPI_PHASE_1EDGE;
}
else {
spiDevice[device].hspi.Init.CLKPolarity = SPI_POLARITY_HIGH;
spiDevice[device].hspi.Init.CLKPhase = SPI_PHASE_2EDGE;
}
if (HAL_SPI_Init(&spiDevice[device].hspi) == HAL_OK)
{
}
}
bool spiInit(SPIDevice device)
{
switch (device) {
case SPIINVALID:
return false;
case SPIDEV_1:
#if defined(USE_SPI_DEVICE_1)
spiInitDevice(device);
return true;
#else
break;
#endif
case SPIDEV_2:
#if defined(USE_SPI_DEVICE_2)
spiInitDevice(device);
return true;
#else
break;
#endif
case SPIDEV_3:
#if defined(USE_SPI_DEVICE_3)
spiInitDevice(device);
return true;
#else
break;
#endif
case SPIDEV_4:
#if defined(USE_SPI_DEVICE_4)
spiInitDevice(device);
return true;
#else
break;
#endif
}
return false;
}
uint32_t spiTimeoutUserCallback(SPI_TypeDef *instance)
{
SPIDevice device = spiDeviceByInstance(instance);
if (device == SPIINVALID) {
return -1;
}
spiDevice[device].errorCount++;
return spiDevice[device].errorCount;
}
/**
* 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 *txData, uint8_t *rxData, int len)
{
SPIDevice device = spiDeviceByInstance(instance);
HAL_StatusTypeDef status;
if (!rxData) { // Tx only
status = HAL_SPI_Transmit(&spiDevice[device].hspi, txData, len, SPI_DEFAULT_TIMEOUT);
} else if (!txData) { // Rx only
status = HAL_SPI_Receive(&spiDevice[device].hspi, rxData, len, SPI_DEFAULT_TIMEOUT);
} else { // Tx and Rx
status = HAL_SPI_TransmitReceive(&spiDevice[device].hspi, txData, rxData, len, SPI_DEFAULT_TIMEOUT);
}
if (status != HAL_OK) {
spiTimeoutUserCallback(instance);
}
return true;
}
static bool spiBusReadBuffer(const busDevice_t *bus, uint8_t *out, int len)
{
const HAL_StatusTypeDef status = HAL_SPI_Receive(bus->busdev_u.spi.handle, out, len, SPI_DEFAULT_TIMEOUT);
if (status != HAL_OK) {
spiTimeoutUserCallback(bus->busdev_u.spi.instance);
}
return true;
}
uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t txByte)
{
uint8_t rxByte;
spiTransfer(instance, &txByte, &rxByte, 1);
return rxByte;
}
static uint8_t spiBusTransferByte(const busDevice_t *bus, uint8_t in)
{
const HAL_StatusTypeDef status = HAL_SPI_TransmitReceive(bus->busdev_u.spi.handle, &in, &in, 1, SPI_DEFAULT_TIMEOUT);
if (status != HAL_OK) {
spiTimeoutUserCallback(bus->busdev_u.spi.instance);
}
return in;
}
bool spiBusTransfer(const busDevice_t *bus, const uint8_t *txData, uint8_t *rxData, int len)
{
IOLo(bus->busdev_u.spi.csnPin);
const HAL_StatusTypeDef status = HAL_SPI_TransmitReceive(bus->busdev_u.spi.handle, txData, rxData, len, SPI_DEFAULT_TIMEOUT);
IOHi(bus->busdev_u.spi.csnPin);
if (status != HAL_OK) {
spiTimeoutUserCallback(bus->busdev_u.spi.instance);
}
return true;
}
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
{
SPIDevice device = spiDeviceByInstance(instance);
if (HAL_SPI_DeInit(&spiDevice[device].hspi) == HAL_OK)
{
}
spiDevice[device].hspi.Init.BaudRatePrescaler = (uint8_t []) {
0, 0,
SPI_BAUDRATEPRESCALER_2, SPI_BAUDRATEPRESCALER_4,
SPI_BAUDRATEPRESCALER_8, SPI_BAUDRATEPRESCALER_16,
SPI_BAUDRATEPRESCALER_32, SPI_BAUDRATEPRESCALER_64,
SPI_BAUDRATEPRESCALER_128, SPI_BAUDRATEPRESCALER_256
}[ffs(divisor | 0x100)];
if (HAL_SPI_Init(&spiDevice[device].hspi) == HAL_OK)
{
}
}
uint16_t spiGetErrorCounter(SPI_TypeDef *instance)
{
SPIDevice device = spiDeviceByInstance(instance);
if (device == SPIINVALID) {
return 0;
}
return spiDevice[device].errorCount;
}
void spiResetErrorCounter(SPI_TypeDef *instance)
{
SPIDevice device = spiDeviceByInstance(instance);
if (device != SPIINVALID) {
spiDevice[device].errorCount = 0;
}
}
bool spiBusWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data)
{
IOLo(bus->busdev_u.spi.csnPin);
spiBusTransferByte(bus, reg);
spiBusTransferByte(bus, data);
IOHi(bus->busdev_u.spi.csnPin);
return true;
}
bool spiBusReadRegisterBuffer(const busDevice_t *bus, uint8_t reg, uint8_t *data, uint8_t length)
{
IOLo(bus->busdev_u.spi.csnPin);
spiBusTransferByte(bus, reg | 0x80); // read transaction
spiBusReadBuffer(bus, data, length);
IOHi(bus->busdev_u.spi.csnPin);
return true;
}
uint8_t spiBusReadRegister(const busDevice_t *bus, uint8_t reg)
{
uint8_t data;
IOLo(bus->busdev_u.spi.csnPin);
spiBusTransferByte(bus, reg | 0x80); // read transaction
spiBusReadBuffer(bus, &data, 1);
IOHi(bus->busdev_u.spi.csnPin);
return data;
}
void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance)
{
bus->busdev_u.spi.instance = instance;
bus->busdev_u.spi.handle = spiHandleByInstance(instance);
}
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, const uint8_t *pData, uint16_t Size)
{
SPIDevice device = spiDeviceByInstance(Instance);
spiDevice[device].hdma.Instance = Stream;
spiDevice[device].hdma.Init.Channel = Channel;
spiDevice[device].hdma.Init.Direction = DMA_MEMORY_TO_PERIPH;
spiDevice[device].hdma.Init.PeriphInc = DMA_PINC_DISABLE;
spiDevice[device].hdma.Init.MemInc = DMA_MINC_ENABLE;
spiDevice[device].hdma.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
spiDevice[device].hdma.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
spiDevice[device].hdma.Init.Mode = DMA_NORMAL;
spiDevice[device].hdma.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
spiDevice[device].hdma.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
spiDevice[device].hdma.Init.PeriphBurst = DMA_PBURST_SINGLE;
spiDevice[device].hdma.Init.MemBurst = DMA_MBURST_SINGLE;
spiDevice[device].hdma.Init.Priority = DMA_PRIORITY_LOW;
HAL_DMA_DeInit(&spiDevice[device].hdma);
HAL_DMA_Init(&spiDevice[device].hdma);
__HAL_DMA_ENABLE(&spiDevice[device].hdma);
__HAL_SPI_ENABLE(&spiDevice[device].hspi);
/* Associate the initialized DMA handle to the spi handle */
__HAL_LINKDMA(&spiDevice[device].hspi, hdmatx, spiDevice[device].hdma);
// DMA TX Interrupt
dmaSetHandler(spiDevice[device].dmaIrqHandler, dmaSPIIRQHandler, NVIC_BUILD_PRIORITY(3, 0), (uint32_t)device);
//HAL_CLEANCACHE(pData,Size);
// And Transmit
HAL_SPI_Transmit_DMA(&spiDevice[device].hspi, CONST_CAST(uint8_t*, pData), Size);
return &spiDevice[device].hdma;
}
#endif

View File

@ -21,7 +21,7 @@
#include <platform.h> #include <platform.h>
#if defined(USE_SPI) && defined(USE_LOWLEVEL_DRIVER) #if defined(USE_SPI)
#include "common/utils.h" #include "common/utils.h"

View File

@ -44,6 +44,7 @@ typedef struct dmaChannelDescriptor_s {
#endif #endif
#if defined(STM32F4) || defined(STM32F7) #if defined(STM32F4) || defined(STM32F7)
uint32_t dmaFlag_IT_TCIF(const DMA_Stream_TypeDef *stream); uint32_t dmaFlag_IT_TCIF(const DMA_Stream_TypeDef *stream);
typedef enum { typedef enum {

View File

@ -156,10 +156,8 @@ bool IORead(IO_t io)
{ {
if (!io) if (!io)
return false; return false;
#if defined(USE_LOWLEVEL_DRIVER) #if defined(USE_HAL_DRIVER)
return (LL_GPIO_ReadInputPort(IO_GPIO(io)) & IO_Pin(io)); return (LL_GPIO_ReadInputPort(IO_GPIO(io)) & IO_Pin(io));
#elif defined(USE_HAL_DRIVER)
return HAL_GPIO_ReadPin(IO_GPIO(io), IO_Pin(io));
#else #else
return (IO_GPIO(io)->IDR & IO_Pin(io)); return (IO_GPIO(io)->IDR & IO_Pin(io));
#endif #endif
@ -169,15 +167,8 @@ void IOWrite(IO_t io, bool hi)
{ {
if (!io) if (!io)
return; return;
#if defined(USE_LOWLEVEL_DRIVER) #if defined(USE_HAL_DRIVER)
LL_GPIO_SetOutputPin(IO_GPIO(io), IO_Pin(io) << (hi ? 0 : 16)); LL_GPIO_SetOutputPin(IO_GPIO(io), IO_Pin(io) << (hi ? 0 : 16));
#elif defined(USE_HAL_DRIVER)
if (hi) {
HAL_GPIO_WritePin(IO_GPIO(io),IO_Pin(io),GPIO_PIN_SET);
}
else {
HAL_GPIO_WritePin(IO_GPIO(io),IO_Pin(io),GPIO_PIN_RESET);
}
#elif defined(STM32F4) #elif defined(STM32F4)
if (hi) { if (hi) {
IO_GPIO(io)->BSRRL = IO_Pin(io); IO_GPIO(io)->BSRRL = IO_Pin(io);
@ -194,10 +185,8 @@ void IOHi(IO_t io)
{ {
if (!io) if (!io)
return; return;
#if defined(USE_LOWLEVEL_DRIVER) #if defined(USE_HAL_DRIVER)
LL_GPIO_SetOutputPin(IO_GPIO(io), IO_Pin(io)); LL_GPIO_SetOutputPin(IO_GPIO(io), IO_Pin(io));
#elif defined(USE_HAL_DRIVER)
HAL_GPIO_WritePin(IO_GPIO(io),IO_Pin(io),GPIO_PIN_SET);
#elif defined(STM32F4) #elif defined(STM32F4)
IO_GPIO(io)->BSRRL = IO_Pin(io); IO_GPIO(io)->BSRRL = IO_Pin(io);
#else #else
@ -209,10 +198,8 @@ void IOLo(IO_t io)
{ {
if (!io) if (!io)
return; return;
#if defined(USE_LOWLEVEL_DRIVER) #if defined(USE_HAL_DRIVER)
LL_GPIO_ResetOutputPin(IO_GPIO(io), IO_Pin(io)); LL_GPIO_ResetOutputPin(IO_GPIO(io), IO_Pin(io));
#elif defined(USE_HAL_DRIVER)
HAL_GPIO_WritePin(IO_GPIO(io),IO_Pin(io),GPIO_PIN_RESET);
#elif defined(STM32F4) #elif defined(STM32F4)
IO_GPIO(io)->BSRRH = IO_Pin(io); IO_GPIO(io)->BSRRH = IO_Pin(io);
#else #else
@ -229,13 +216,11 @@ void IOToggle(IO_t io)
// Read pin state from ODR but write to BSRR because it only changes the pins // Read pin state from ODR but write to BSRR because it only changes the pins
// high in the mask value rather than all pins. XORing ODR directly risks // high in the mask value rather than all pins. XORing ODR directly risks
// setting other pins incorrectly because it change all pins' state. // setting other pins incorrectly because it change all pins' state.
#if defined(USE_LOWLEVEL_DRIVER) #if defined(USE_HAL_DRIVER)
if (LL_GPIO_ReadOutputPort(IO_GPIO(io)) & mask) if (LL_GPIO_ReadOutputPort(IO_GPIO(io)) & mask) {
mask <<= 16; // bit is set, shift mask to reset half mask <<= 16; // bit is set, shift mask to reset half
}
LL_GPIO_SetOutputPin(IO_GPIO(io), mask); LL_GPIO_SetOutputPin(IO_GPIO(io), mask);
#elif defined(USE_HAL_DRIVER)
(void)mask;
HAL_GPIO_TogglePin(IO_GPIO(io),IO_Pin(io));
#elif defined(STM32F4) #elif defined(STM32F4)
if (IO_GPIO(io)->ODR & mask) { if (IO_GPIO(io)->ODR & mask) {
IO_GPIO(io)->BSRRH = mask; IO_GPIO(io)->BSRRH = mask;
@ -307,7 +292,6 @@ void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af)
rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc; rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
RCC_ClockCmd(rcc, ENABLE); RCC_ClockCmd(rcc, ENABLE);
#if defined(USE_LOWLEVEL_DRIVER)
LL_GPIO_InitTypeDef init = { LL_GPIO_InitTypeDef init = {
.Pin = IO_Pin(io), .Pin = IO_Pin(io),
.Mode = (cfg >> 0) & 0x13, .Mode = (cfg >> 0) & 0x13,
@ -317,16 +301,6 @@ void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af)
}; };
LL_GPIO_Init(IO_GPIO(io), &init); LL_GPIO_Init(IO_GPIO(io), &init);
#else
GPIO_InitTypeDef init = {
.Pin = IO_Pin(io),
.Mode = (cfg >> 0) & 0x13,
.Speed = (cfg >> 2) & 0x03,
.Pull = (cfg >> 5) & 0x03,
.Alternate = af
};
HAL_GPIO_Init(IO_GPIO(io), &init);
#endif
} }
#elif defined(STM32F3) || defined(STM32F4) #elif defined(STM32F3) || defined(STM32F4)

View File

@ -104,11 +104,8 @@ typedef struct sdcard_t {
static sdcard_t sdcard; static sdcard_t sdcard;
#ifdef SDCARD_DMA_CHANNEL_TX #if defined(SDCARD_DMA_CHANNEL_TX) || defined(SDCARD_DMA_TX)
static bool useDMAForTx; static bool useDMAForTx;
#if defined(USE_HAL_DRIVER)
DMA_HandleTypeDef *sdDMAHandle;
#endif
#else #else
// DMA channel not available so we can hard-code this to allow the non-DMA paths to be stripped by optimization // DMA channel not available so we can hard-code this to allow the non-DMA paths to be stripped by optimization
static const bool useDMAForTx = false; static const bool useDMAForTx = false;
@ -413,47 +410,72 @@ static void sdcard_sendDataBlockBegin(const uint8_t *buffer, bool multiBlockWrit
spiTransferByte(SDCARD_SPI_INSTANCE, multiBlockWrite ? SDCARD_MULTIPLE_BLOCK_WRITE_START_TOKEN : SDCARD_SINGLE_BLOCK_WRITE_START_TOKEN); spiTransferByte(SDCARD_SPI_INSTANCE, multiBlockWrite ? SDCARD_MULTIPLE_BLOCK_WRITE_START_TOKEN : SDCARD_SINGLE_BLOCK_WRITE_START_TOKEN);
if (useDMAForTx) { if (useDMAForTx) {
#ifdef SDCARD_DMA_CHANNEL_TX #if defined(SDCARD_DMA_TX) && defined(USE_HAL_DRIVER)
#if defined(USE_HAL_DRIVER)
sdDMAHandle = spiSetDMATransmit(SDCARD_DMA_CHANNEL_TX, SDCARD_DMA_CHANNEL, SDCARD_SPI_INSTANCE, buffer, SDCARD_BLOCK_SIZE); #ifdef SDCARD_DMA_CLK
#else LL_AHB1_GRP1_EnableClock(SDCARD_DMA_CLK);
#endif
LL_DMA_InitTypeDef init;
LL_DMA_StructInit(&init);
init.Channel = SDCARD_DMA_CHANNEL;
init.Mode = LL_DMA_MODE_NORMAL;
init.Direction = LL_DMA_DIRECTION_MEMORY_TO_PERIPH;
init.PeriphOrM2MSrcAddress = (uint32_t)&SDCARD_SPI_INSTANCE->DR;
init.Priority = LL_DMA_PRIORITY_LOW;
init.PeriphOrM2MSrcIncMode = LL_DMA_PERIPH_NOINCREMENT;
init.PeriphOrM2MSrcDataSize = LL_DMA_PDATAALIGN_BYTE;
init.MemoryOrM2MDstAddress = (uint32_t)buffer;
init.MemoryOrM2MDstIncMode = LL_DMA_MEMORY_INCREMENT;
init.MemoryOrM2MDstDataSize = SDCARD_BLOCK_SIZE;
LL_DMA_DeInit(SDCARD_DMA_TX, SDCARD_DMA_STREAM_TX);
LL_DMA_Init(SDCARD_DMA_TX, SDCARD_DMA_STREAM_TX, &init);
LL_DMA_EnableStream(SDCARD_DMA_TX, SDCARD_DMA_STREAM_TX);
LL_SPI_EnableDMAReq_TX(SDCARD_SPI_INSTANCE);
#elif defined(SDCARD_DMA_CHANNEL_TX)
// Queue the transmission of the sector payload // Queue the transmission of the sector payload
#ifdef SDCARD_DMA_CLK #ifdef SDCARD_DMA_CLK
RCC_AHB1PeriphClockCmd(SDCARD_DMA_CLK, ENABLE); RCC_AHB1PeriphClockCmd(SDCARD_DMA_CLK, ENABLE);
#endif #endif
DMA_InitTypeDef DMA_InitStructure; DMA_InitTypeDef init;
DMA_StructInit(&DMA_InitStructure); DMA_StructInit(&init);
#ifdef SDCARD_DMA_CHANNEL #ifdef SDCARD_DMA_CHANNEL
DMA_InitStructure.DMA_Channel = SDCARD_DMA_CHANNEL; init.DMA_Channel = SDCARD_DMA_CHANNEL;
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t) buffer; init.DMA_Memory0BaseAddr = (uint32_t) buffer;
DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral; init.DMA_DIR = DMA_DIR_MemoryToPeripheral;
#else #else
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; init.DMA_M2M = DMA_M2M_Disable;
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t) buffer; init.DMA_MemoryBaseAddr = (uint32_t) buffer;
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST; init.DMA_DIR = DMA_DIR_PeripheralDST;
#endif #endif
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t) &SDCARD_SPI_INSTANCE->DR; init.DMA_PeripheralBaseAddr = (uint32_t) &SDCARD_SPI_INSTANCE->DR;
DMA_InitStructure.DMA_Priority = DMA_Priority_Low; init.DMA_Priority = DMA_Priority_Low;
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; init.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; init.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; init.DMA_MemoryInc = DMA_MemoryInc_Enable;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; init.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
DMA_InitStructure.DMA_BufferSize = SDCARD_BLOCK_SIZE; init.DMA_BufferSize = SDCARD_BLOCK_SIZE;
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal; init.DMA_Mode = DMA_Mode_Normal;
DMA_DeInit(SDCARD_DMA_CHANNEL_TX); DMA_DeInit(SDCARD_DMA_CHANNEL_TX);
DMA_Init(SDCARD_DMA_CHANNEL_TX, &DMA_InitStructure); DMA_Init(SDCARD_DMA_CHANNEL_TX, &init);
DMA_Cmd(SDCARD_DMA_CHANNEL_TX, ENABLE); DMA_Cmd(SDCARD_DMA_CHANNEL_TX, ENABLE);
SPI_I2S_DMACmd(SDCARD_SPI_INSTANCE, SPI_I2S_DMAReq_Tx, ENABLE); SPI_I2S_DMACmd(SDCARD_SPI_INSTANCE, SPI_I2S_DMAReq_Tx, ENABLE);
#endif #endif
#endif } else {
}
else {
// Send the first chunk now // Send the first chunk now
spiTransfer(SDCARD_SPI_INSTANCE, buffer, NULL, SDCARD_NON_DMA_CHUNK_SIZE); spiTransfer(SDCARD_SPI_INSTANCE, buffer, NULL, SDCARD_NON_DMA_CHUNK_SIZE);
} }
@ -547,7 +569,12 @@ static bool sdcard_checkInitDone(void)
*/ */
void sdcard_init(bool useDMA) void sdcard_init(bool useDMA)
{ {
#ifdef SDCARD_DMA_CHANNEL_TX #if defined(SDCARD_DMA_TX)
useDMAForTx = useDMA;
if (useDMAForTx) {
dmaInit(dmaGetIdentifier(SDCARD_DMA_STREAM_TX_FULL), OWNER_SDCARD, 0);
}
#elif defined(SDCARD_DMA_CHANNEL_TX)
useDMAForTx = useDMA; useDMAForTx = useDMA;
if (useDMAForTx) { if (useDMAForTx) {
dmaInit(dmaGetIdentifier(SDCARD_DMA_CHANNEL_TX), OWNER_SDCARD, 0); dmaInit(dmaGetIdentifier(SDCARD_DMA_CHANNEL_TX), OWNER_SDCARD, 0);
@ -736,17 +763,11 @@ bool sdcard_poll(void)
// Have we finished sending the write yet? // Have we finished sending the write yet?
sendComplete = false; sendComplete = false;
#ifdef SDCARD_DMA_CHANNEL_TX #ifdef SDCARD_DMA_TX
#if defined(USE_HAL_DRIVER) // TODO : need to verify this
//if (useDMAForTx && __HAL_DMA_GET_FLAG(sdDMAHandle, SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG) == SET) { if (useDMAForTx && LL_DMA_IsEnabledStream(SDCARD_DMA_TX, SDCARD_DMA_STREAM_TX)) {
//if (useDMAForTx && HAL_DMA_PollForTransfer(sdDMAHandle, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY) == HAL_OK) {
if (useDMAForTx && (sdDMAHandle->State == HAL_DMA_STATE_READY)) {
//__HAL_DMA_CLEAR_FLAG(sdDMAHandle, SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG);
//__HAL_DMA_DISABLE(sdDMAHandle);
// Drain anything left in the Rx FIFO (we didn't read it during the write) // Drain anything left in the Rx FIFO (we didn't read it during the write)
while (__HAL_SPI_GET_FLAG(spiHandleByInstance(SDCARD_SPI_INSTANCE), SPI_FLAG_RXNE) == SET) { while (LL_SPI_IsActiveFlag_RXNE(SDCARD_SPI_INSTANCE)) {
SDCARD_SPI_INSTANCE->DR; SDCARD_SPI_INSTANCE->DR;
} }
@ -754,11 +775,11 @@ bool sdcard_poll(void)
while (spiIsBusBusy(SDCARD_SPI_INSTANCE)) { while (spiIsBusBusy(SDCARD_SPI_INSTANCE)) {
} }
HAL_SPI_DMAStop(spiHandleByInstance(SDCARD_SPI_INSTANCE)); LL_SPI_DisableDMAReq_TX(SDCARD_SPI_INSTANCE);
sendComplete = true; sendComplete = true;
} }
#else #elif defined(SDCARD_DMA_CHANNEL_TX)
#ifdef SDCARD_DMA_CHANNEL #ifdef SDCARD_DMA_CHANNEL
if (useDMAForTx && DMA_GetFlagStatus(SDCARD_DMA_CHANNEL_TX, SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG) == SET) { if (useDMAForTx && DMA_GetFlagStatus(SDCARD_DMA_CHANNEL_TX, SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG) == SET) {
DMA_ClearFlag(SDCARD_DMA_CHANNEL_TX, SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG); DMA_ClearFlag(SDCARD_DMA_CHANNEL_TX, SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG);
@ -782,7 +803,6 @@ bool sdcard_poll(void)
sendComplete = true; sendComplete = true;
} }
#endif
#endif #endif
if (!useDMAForTx) { if (!useDMAForTx) {
// Send another chunk // Send another chunk

View File

@ -27,6 +27,9 @@
#include "stm32f7xx_ll_spi.h" #include "stm32f7xx_ll_spi.h"
#include "stm32f7xx_ll_gpio.h" #include "stm32f7xx_ll_gpio.h"
#include "stm32f7xx_ll_dma.h"
#include "stm32f7xx_ll_rcc.h"
#include "stm32f7xx_ll_bus.h"
// Chip Unique ID on F7 // Chip Unique ID on F7
#if defined(STM32F722xx) #if defined(STM32F722xx)

View File

@ -125,9 +125,12 @@
// Divide to under 25MHz for normal operation: // Divide to under 25MHz for normal operation:
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 27MHz #define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 27MHz
#define SDCARD_DMA_CHANNEL_TX DMA2_Stream1 #define SDCARD_DMA_STREAM_TX_FULL DMA2_Stream1
#define SDCARD_DMA_TX DMA2
#define SDCARD_DMA_STREAM_TX 1
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF1_5 #define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF1_5
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA2 #define SDCARD_DMA_CLK LL_AHB1_GRP1_PERIPH_DMA2
#define SDCARD_DMA_CHANNEL DMA_CHANNEL_4 #define SDCARD_DMA_CHANNEL DMA_CHANNEL_4
#define USE_I2C #define USE_I2C

View File

@ -98,7 +98,6 @@
#define ESCSERIAL_TIMER_TX_PIN PC7 // (Hardware=0, PPM) #define ESCSERIAL_TIMER_TX_PIN PC7 // (Hardware=0, PPM)
#define USE_SPI #define USE_SPI
#define USE_LOWLEVEL_DRIVER
#define USE_SPI_DEVICE_1 #define USE_SPI_DEVICE_1
#define SPI1_NSS_PIN PC4 #define SPI1_NSS_PIN PC4