1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-12 19:10:27 +03:00

f7: use hal for sdio

This commit is contained in:
Marcelo Bezerra 2024-12-10 00:02:19 +01:00 committed by bkleiner
parent 2dad829481
commit 3561feeb9f
15 changed files with 207 additions and 2259 deletions

View file

@ -38,6 +38,8 @@ set(STM32F7_HAL_SRC
stm32f7xx_ll_tim.c
stm32f7xx_ll_usb.c
stm32f7xx_ll_utils.c
stm32f7xx_hal_sd.c
stm32f7xx_ll_sdmmc.c
)
list(TRANSFORM STM32F7_HAL_SRC PREPEND "${STM32F7_HAL_DIR}/Src/")
@ -74,7 +76,7 @@ main_sources(STM32F7_SRC
drivers/system_stm32f7xx.c
drivers/serial_uart_stm32f7xx.c
drivers/serial_uart_hal.c
drivers/sdcard/sdmmc_sdio_f7xx.c
drivers/sdcard/sdmmc_sdio_hal.c
)
main_sources(STM32F7_MSC_SRC

View file

@ -161,7 +161,7 @@ main_sources(STM32H7_SRC
drivers/serial_uart_stm32h7xx.c
drivers/serial_uart_hal.c
drivers/sdio.h
drivers/sdcard/sdmmc_sdio_h7xx.c
drivers/sdcard/sdmmc_sdio_hal.c
)
main_sources(STM32H7_MSC_SRC

View file

@ -95,14 +95,21 @@ static bool sdcardSdio_isFunctional(void)
*/
static void sdcardSdio_reset(void)
{
if (SD_Init() != 0) {
sdcard.failureCount++;
if (sdcard.failureCount >= SDCARD_MAX_CONSECUTIVE_FAILURES || !sdcard_isInserted()) {
sdcard.state = SDCARD_STATE_NOT_PRESENT;
} else {
sdcard.operationStartTime = millis();
sdcard.state = SDCARD_STATE_RESET;
}
if (!sdcard_isInserted()) {
sdcard.state = SDCARD_STATE_NOT_PRESENT;
return;
}
if (SD_Init() != SD_OK) {
sdcard.state = SDCARD_STATE_NOT_PRESENT;
return;
}
sdcard.failureCount++;
if (sdcard.failureCount >= SDCARD_MAX_CONSECUTIVE_FAILURES) {
sdcard.state = SDCARD_STATE_NOT_PRESENT;
} else {
sdcard.operationStartTime = millis();
sdcard.state = SDCARD_STATE_RESET;
}
}
@ -573,17 +580,13 @@ void sdcardSdio_init(void)
return;
}
if (!SD_Initialize_LL(sdcard.dma->ref)) {
if (!SD_Initialize_LL(sdcard.dma)) {
sdcard.dma = NULL;
sdcard.state = SDCARD_STATE_NOT_PRESENT;
return;
}
#else
if (!SD_Initialize_LL(0)) {
sdcard.state = SDCARD_STATE_NOT_PRESENT;
return;
}
#endif
// We don't support hot insertion
if (!sdcard_isInserted()) {
sdcard.state = SDCARD_STATE_NOT_PRESENT;

View file

@ -31,22 +31,7 @@
#if defined(USE_SDCARD_SDIO)
#include "platform.h"
#ifdef STM32F4
#include "stm32f4xx.h"
#endif
#ifdef STM32F7
#include "stm32f7xx.h"
#endif
#ifdef STM32H7
#include "stm32h7xx.h"
#endif
#ifdef AT32F43x
#include "at32f435_437.h"
#endif
#include "drivers/dma.h"
/* SDCARD pinouts
*
@ -221,9 +206,9 @@ extern SD_CardType_t SD_CardType;
#ifdef AT32F43x
// TODO:AT32 TARGES NOT USE SD CARD ANT TF CARD FOR NOW
void SD_Initialize_LL (dma_channel_type *dma);
void SD_Initialize_LL (DMA_t dma);
#else
bool SD_Initialize_LL (DMA_Stream_TypeDef *dma);
bool SD_Initialize_LL (DMA_t dma);
#endif
bool SD_Init(void);
bool SD_IsDetected(void);

View file

@ -1356,8 +1356,10 @@ static SD_Error_t SD_FindSCR(uint32_t *pSCR)
/**
* @brief Initialize the SDIO module, DMA, and IO
*/
bool SD_Initialize_LL(DMA_Stream_TypeDef *dmaRef)
bool SD_Initialize_LL(DMA_t dma)
{
DMA_Stream_TypeDef *dmaRef = dma->ref;
// Sanity check DMA stread - we only support two possible
if (((uint32_t)dmaRef != (uint32_t)DMA2_Stream3) && ((uint32_t)dmaRef != (uint32_t)DMA2_Stream6)) {
return false;

File diff suppressed because it is too large Load diff

View file

@ -33,7 +33,6 @@
#ifdef USE_SDCARD_SDIO
#include "sdmmc_sdio.h"
#include "stm32h7xx.h"
#include "drivers/sdio.h"
#include "drivers/io.h"
@ -53,12 +52,12 @@ typedef struct SD_Handle_s
volatile uint32_t TXCplt; // SD TX Complete is equal 0 when no transfer
} SD_Handle_t;
SD_HandleTypeDef hsd1;
SD_CardInfo_t SD_CardInfo;
SD_CardType_t SD_CardType;
static SD_Handle_t SD_Handle;
static SD_Handle_t SD_Handle;
static DMA_HandleTypeDef sd_dma;
static SD_HandleTypeDef hsd;
typedef struct sdioPin_s {
ioTag_t pin;
@ -75,6 +74,18 @@ typedef struct sdioPin_s {
#define SDIO_MAX_PINDEFS 2
#define IOCFG_SDMMC IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_NOPULL)
#ifdef STM32F7
#define SDMMC_CLK_DIV SDMMC_TRANSFER_CLK_DIV
#else
#if defined(SDCARD_SDIO_NORMAL_SPEED)
#define SDMMC_CLK_DIV SDMMC_NSpeed_CLK_DIV
#else
#define SDMMC_CLK_DIV SDMMC_HSpeed_CLK_DIV
#endif
#endif
typedef struct sdioHardware_s {
SDMMC_TypeDef *instance;
IRQn_Type irqn;
@ -90,6 +101,7 @@ typedef struct sdioHardware_s {
#define PINDEF(device, pin, afnum) { DEFIO_TAG_E(pin), GPIO_AF ## afnum ## _SDMMC ## device }
#ifdef STM32H7
static const sdioHardware_t sdioPinHardware[SDIODEV_COUNT] = {
{
.instance = SDMMC1,
@ -112,6 +124,36 @@ static const sdioHardware_t sdioPinHardware[SDIODEV_COUNT] = {
.sdioPinD3 = { PINDEF(2, PB4, 9) },
}
};
#endif
#ifdef STM32F7
static const sdioHardware_t sdioPinHardware[SDIODEV_COUNT] = {
{
.instance = SDMMC1,
.irqn = SDMMC1_IRQn,
.sdioPinCK = { PINDEF(1, PC12, 12) },
.sdioPinCMD = { PINDEF(1, PD2, 12) },
.sdioPinD0 = { PINDEF(1, PC8, 12) },
.sdioPinD1 = { PINDEF(1, PC9, 12) },
.sdioPinD2 = { PINDEF(1, PC10, 12) },
.sdioPinD3 = { PINDEF(1, PC11, 12) },
//.sdioPinD4 = { PINDEF(1, PB8, 12) },
//.sdioPinD5 = { PINDEF(1, PB9, 12) },
//.sdioPinD6 = { PINDEF(1, PC7, 12) },
//.sdioPinD7 = { PINDEF(1, PC11, 12) },
},
{
.instance = SDMMC2,
.irqn = SDMMC2_IRQn,
.sdioPinCK = { PINDEF(2, PD6, 11) },
.sdioPinCMD = { PINDEF(2, PD7, 11) },
.sdioPinD0 = { PINDEF(2, PB14, 10), PINDEF(2, PG0, 11) },
.sdioPinD1 = { PINDEF(2, PB15, 10), PINDEF(2, PG10, 11) },
.sdioPinD2 = { PINDEF(2, PB3, 10), PINDEF(2, PG11, 10) },
.sdioPinD3 = { PINDEF(2, PB4, 10), PINDEF(2, PG12, 11) },
}
};
#endif
#undef PINDEF
@ -137,21 +179,61 @@ void sdioPinConfigure(void)
#else
sdioPin[SDIO_PIN_CMD] = sdioHardware->sdioPinCMD[0];
#endif
sdioPin[SDIO_PIN_D0] = sdioHardware->sdioPinD0[0];
sdioPin[SDIO_PIN_D0] = sdioHardware->sdioPinD0[0];
const IO_t clk = IOGetByTag(sdioPin[SDIO_PIN_CK].pin);
const IO_t cmd = IOGetByTag(sdioPin[SDIO_PIN_CMD].pin);
const IO_t d0 = IOGetByTag(sdioPin[SDIO_PIN_D0].pin);
IOInit(clk, OWNER_SDCARD, RESOURCE_NONE, 0);
IOInit(cmd, OWNER_SDCARD, RESOURCE_NONE, 0);
IOInit(d0, OWNER_SDCARD, RESOURCE_NONE, 0);
#ifdef SDCARD_SDIO_4BIT
sdioPin[SDIO_PIN_D1] = sdioHardware->sdioPinD1[0];
sdioPin[SDIO_PIN_D2] = sdioHardware->sdioPinD2[0];
sdioPin[SDIO_PIN_D3] = sdioHardware->sdioPinD3[0];
const IO_t d1 = IOGetByTag(sdioPin[SDIO_PIN_D1].pin);
const IO_t d2 = IOGetByTag(sdioPin[SDIO_PIN_D2].pin);
const IO_t d3 = IOGetByTag(sdioPin[SDIO_PIN_D3].pin);
IOInit(d1, OWNER_SDCARD, RESOURCE_NONE, 0);
IOInit(d2, OWNER_SDCARD, RESOURCE_NONE, 0);
IOInit(d3, OWNER_SDCARD, RESOURCE_NONE, 0);
#endif
//
// Setting all the SDIO pins to high for a short time results in more robust
// initialisation.
//
IOHi(d0);
IOConfigGPIO(d0, IOCFG_OUT_PP);
#ifdef SDCARD_SDIO_4BIT
IOHi(d1);
IOHi(d2);
IOHi(d3);
IOConfigGPIO(d1, IOCFG_OUT_PP);
IOConfigGPIO(d2, IOCFG_OUT_PP);
IOConfigGPIO(d3, IOCFG_OUT_PP);
#endif
IOHi(clk);
IOHi(cmd);
IOConfigGPIO(clk, IOCFG_OUT_PP);
IOConfigGPIO(cmd, IOCFG_OUT_PP);
}
#define IOCFG_SDMMC IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_NOPULL)
void SDMMC_DMA_IRQHandler(DMA_t channel)
{
UNUSED(channel);
HAL_DMA_IRQHandler(&sd_dma);
}
void HAL_SD_MspInit(SD_HandleTypeDef* hsd)
{
UNUSED(hsd);
if (!sdioHardware) {
return;
}
@ -187,100 +269,89 @@ void HAL_SD_MspInit(SD_HandleTypeDef* hsd)
IOConfigGPIOAF(d3, IOCFG_SDMMC, sdioPin[SDIO_PIN_D3].af);
#endif
HAL_NVIC_SetPriority(sdioHardware->irqn, 0, 0);
#ifdef STM32F7
sd_dma.Init.Direction = DMA_PERIPH_TO_MEMORY;
sd_dma.Init.PeriphInc = DMA_PINC_DISABLE;
sd_dma.Init.MemInc = DMA_MINC_ENABLE;
sd_dma.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD;
sd_dma.Init.MemDataAlignment = DMA_MDATAALIGN_WORD;
sd_dma.Init.Mode = DMA_PFCTRL;
sd_dma.Init.Priority = DMA_PRIORITY_LOW;
sd_dma.Init.FIFOMode = DMA_FIFOMODE_ENABLE;
sd_dma.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL;
sd_dma.Init.MemBurst = DMA_MBURST_INC4;
sd_dma.Init.PeriphBurst = DMA_PBURST_INC4;
dmaInit(dmaGetByRef(sd_dma.Instance), OWNER_SDCARD, 0);
if (HAL_DMA_Init(&sd_dma) != HAL_OK) {
return;
}
dmaSetHandler(dmaGetByRef(sd_dma.Instance), SDMMC_DMA_IRQHandler, 1, 0);
__HAL_LINKDMA(hsd, hdmarx, sd_dma);
__HAL_LINKDMA(hsd, hdmatx, sd_dma);
#else
UNUSED(hsd);
#endif
HAL_NVIC_SetPriority(sdioHardware->irqn, 2, 0);
HAL_NVIC_EnableIRQ(sdioHardware->irqn);
}
void SDIO_GPIO_Init(void)
{
if (!sdioHardware) {
return;
}
const IO_t clk = IOGetByTag(sdioPin[SDIO_PIN_CK].pin);
const IO_t cmd = IOGetByTag(sdioPin[SDIO_PIN_CMD].pin);
const IO_t d0 = IOGetByTag(sdioPin[SDIO_PIN_D0].pin);
const IO_t d1 = IOGetByTag(sdioPin[SDIO_PIN_D1].pin);
const IO_t d2 = IOGetByTag(sdioPin[SDIO_PIN_D2].pin);
const IO_t d3 = IOGetByTag(sdioPin[SDIO_PIN_D3].pin);
IOInit(clk, OWNER_SDCARD, RESOURCE_NONE, 0);
IOInit(cmd, OWNER_SDCARD, RESOURCE_NONE, 0);
IOInit(d0, OWNER_SDCARD, RESOURCE_NONE, 0);
#ifdef SDCARD_SDIO_4BIT
IOInit(d1, OWNER_SDCARD, RESOURCE_NONE, 0);
IOInit(d2, OWNER_SDCARD, RESOURCE_NONE, 0);
IOInit(d3, OWNER_SDCARD, RESOURCE_NONE, 0);
#endif
//
// Setting all the SDIO pins to high for a short time results in more robust initialisation.
//
IOHi(d0);
IOConfigGPIO(d0, IOCFG_OUT_PP);
#ifdef SDCARD_SDIO_4BIT
IOHi(d1);
IOHi(d2);
IOHi(d3);
IOConfigGPIO(d1, IOCFG_OUT_PP);
IOConfigGPIO(d2, IOCFG_OUT_PP);
IOConfigGPIO(d3, IOCFG_OUT_PP);
#endif
IOHi(clk);
IOHi(cmd);
IOConfigGPIO(clk, IOCFG_OUT_PP);
IOConfigGPIO(cmd, IOCFG_OUT_PP);
}
bool SD_Initialize_LL(DMA_Stream_TypeDef *dma)
bool SD_Initialize_LL(DMA_t dma)
{
#ifdef STM32F7
sd_dma.Instance = dma->ref;
sd_dma.Init.Channel = dmaGetChannelByTag(SDCARD_SDIO_DMA);
#else
UNUSED(dma);
#endif
return true;
}
bool SD_GetState(void)
{
HAL_SD_CardStateTypedef cardState = HAL_SD_GetCardState(&hsd1);
HAL_SD_CardStateTypedef cardState = HAL_SD_GetCardState(&hsd);
return (cardState == HAL_SD_CARD_TRANSFER);
}
bool SD_Init(void)
{
memset(&hsd1, 0, sizeof(hsd1));
memset(&hsd, 0, sizeof(hsd));
hsd1.Instance = sdioHardware->instance;
hsd.Instance = sdioHardware->instance;
// falling seems to work better ?? no idea whats "right" here
hsd1.Init.ClockEdge = SDMMC_CLOCK_EDGE_FALLING;
hsd.Init.ClockEdge = SDMMC_CLOCK_EDGE_FALLING;
// drastically increases the time to respond from the sdcard
// lets leave it off
hsd1.Init.ClockPowerSave = SDMMC_CLOCK_POWER_SAVE_DISABLE;
#ifdef SDCARD_SDIO_4BIT
hsd1.Init.BusWide = SDMMC_BUS_WIDE_4B;
#else
hsd1.Init.BusWide = SDMMC_BUS_WIDE_1B;
#endif
hsd1.Init.HardwareFlowControl = SDMMC_HARDWARE_FLOW_CONTROL_ENABLE;
#ifdef SDCARD_SDIO_NORMAL_SPEED
hsd1.Init.ClockDiv = SDMMC_NSpeed_CLK_DIV;
#else
hsd1.Init.ClockDiv = SDMMC_HSpeed_CLK_DIV; // lets not go too crazy :)
hsd.Init.ClockPowerSave = SDMMC_CLOCK_POWER_SAVE_DISABLE;
#ifdef STM32F7
hsd.Init.ClockBypass = SDMMC_CLOCK_BYPASS_DISABLE;
#endif
hsd.Init.BusWide = SDMMC_BUS_WIDE_1B;
hsd.Init.HardwareFlowControl = SDMMC_HARDWARE_FLOW_CONTROL_ENABLE;
hsd.Init.ClockDiv = SDMMC_CLK_DIV;
// Will call HAL_SD_MspInit
const HAL_StatusTypeDef status = HAL_SD_Init(&hsd1);
if (status != HAL_OK) {
if (HAL_SD_Init(&hsd) != HAL_OK) {
return SD_ERROR;
}
if (hsd.SdCard.BlockNbr == 0) {
return SD_ERROR;
}
switch(hsd1.SdCard.CardType) {
#ifdef SDCARD_SDIO_4BIT
if (HAL_SD_ConfigWideBusOperation(&hsd, SDMMC_BUS_WIDE_4B) != HAL_OK) {
return SD_ERROR;
}
#endif
switch(hsd.SdCard.CardType) {
case CARD_SDSC:
switch (hsd1.SdCard.CardVersion) {
switch (hsd.SdCard.CardVersion) {
case CARD_V1_X:
SD_CardType = SD_STD_CAPACITY_V1_1;
break;
@ -300,11 +371,11 @@ bool SD_Init(void)
return SD_ERROR;
}
// STATIC_ASSERT(sizeof(SD_Handle.CSD) == sizeof(hsd1.CSD), hal-csd-size-error);
memcpy(&SD_Handle.CSD, &hsd1.CSD, sizeof(SD_Handle.CSD));
// STATIC_ASSERT(sizeof(SD_Handle.CSD) == sizeof(hsd.CSD), hal-csd-size-error);
memcpy(&SD_Handle.CSD, &hsd.CSD, sizeof(SD_Handle.CSD));
// STATIC_ASSERT(sizeof(SD_Handle.CID) == sizeof(hsd1.CID), hal-cid-size-error);
memcpy(&SD_Handle.CID, &hsd1.CID, sizeof(SD_Handle.CID));
// STATIC_ASSERT(sizeof(SD_Handle.CID) == sizeof(hsd.CID), hal-cid-size-error);
memcpy(&SD_Handle.CID, &hsd.CID, sizeof(SD_Handle.CID));
return SD_OK;
}
@ -529,15 +600,24 @@ SD_Error_t SD_WriteBlocks_DMA(uint64_t WriteAddress, uint32_t *buffer, uint32_t
return SD_ERROR; // unsupported.
}
#ifndef STM32F7
if ((uint32_t)buffer & 0x1f) {
return SD_ADDR_MISALIGNED;
}
#endif
// Ensure the data is flushed to main memory
SCB_CleanDCache_by_Addr(buffer, NumberOfBlocks * BlockSize);
HAL_StatusTypeDef status;
if ((status = HAL_SD_WriteBlocks_DMA(&hsd1, (uint8_t *)buffer, WriteAddress, NumberOfBlocks)) != HAL_OK) {
#ifdef STM32F7
if (sd_dma.Init.Direction != DMA_MEMORY_TO_PERIPH) {
sd_dma.Init.Direction = DMA_MEMORY_TO_PERIPH;
if (HAL_DMA_Init(&sd_dma) != HAL_OK) {
return SD_ERROR;
}
}
#endif
if (HAL_SD_WriteBlocks_DMA(&hsd, (uint8_t *)buffer, WriteAddress, NumberOfBlocks) != HAL_OK) {
return SD_ERROR;
}
@ -560,9 +640,11 @@ SD_Error_t SD_ReadBlocks_DMA(uint64_t ReadAddress, uint32_t *buffer, uint32_t Bl
return SD_ERROR; // unsupported.
}
#ifndef STM32F7
if ((uint32_t)buffer & 0x1f) {
return SD_ADDR_MISALIGNED;
}
#endif
SD_Handle.RXCplt = 1;
@ -570,8 +652,15 @@ SD_Error_t SD_ReadBlocks_DMA(uint64_t ReadAddress, uint32_t *buffer, uint32_t Bl
sdReadParameters.BlockSize = BlockSize;
sdReadParameters.NumberOfBlocks = NumberOfBlocks;
HAL_StatusTypeDef status;
if ((status = HAL_SD_ReadBlocks_DMA(&hsd1, (uint8_t *)buffer, ReadAddress, NumberOfBlocks)) != HAL_OK) {
#ifdef STM32F7
if (sd_dma.Init.Direction != DMA_PERIPH_TO_MEMORY) {
sd_dma.Init.Direction = DMA_PERIPH_TO_MEMORY;
if (HAL_DMA_Init(&sd_dma) != HAL_OK) {
return SD_ERROR;
}
}
#endif
if (HAL_SD_ReadBlocks_DMA(&hsd, (uint8_t *)buffer, ReadAddress, NumberOfBlocks) != HAL_OK) {
return SD_ERROR;
}
@ -619,12 +708,12 @@ void HAL_SD_AbortCallback(SD_HandleTypeDef *hsd)
void SDMMC1_IRQHandler(void)
{
HAL_SD_IRQHandler(&hsd1);
HAL_SD_IRQHandler(&hsd);
}
void SDMMC2_IRQHandler(void)
{
HAL_SD_IRQHandler(&hsd1);
HAL_SD_IRQHandler(&hsd);
}
#endif

View file

@ -29,7 +29,6 @@ typedef enum {
#define SDIODEV_COUNT 2
#if defined(STM32H7)
#if defined(STM32H7) || defined(STM32F7)
void sdioPinConfigure(void);
void SDIO_GPIO_Init(void);
#endif

View file

@ -1,241 +0,0 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software 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 and Betaflight are distributed in the hope that they
* 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
/*
* Original author: Alain (https://github.com/aroyer-qc)
* Modified for F4 and BF source: Chris Hockuba (https://github.com/conkerkh)
*
*/
#ifndef __fatfs_sd_sdio_H__
#define __fatfs_sd_sdio_H__
#include <stdint.h>
#include "platform.h"
#ifdef STM32F4
#include "stm32f4xx.h"
#endif
#ifdef STM32F7
#include "stm32f7xx.h"
#endif
/* SDCARD pinouts
*
* SD CARD PINS
_________________
/ 1 2 3 4 5 6 7 8 | NR |SDIO INTERFACE
/ | |NAME STM32F746 DESCRIPTION
/ 9 | | 4-BIT 1-BIT
| | |
| | 1 |CD/DAT3 PC11 - Connector data line 3
| | 2 |CMD PD2 PD2 Command/Response line
| | 3 |VSS1 GND GND GND
| SD CARD Pinout | 4 |VDD 3.3V 3.3V 3.3V Power supply
| | 5 |CLK PC12 PC12 Clock
| | 6 |VSS2 GND GND GND
| | 7 |DAT0 PC8 PC8 Connector data line 0
| | 8 |DAT1 PC9 - Connector data line 1
|___________________| 9 |DAT2 PC10 - Connector data line 2
*/
/* Define(s) --------------------------------------------------------------------------------------------------------*/
//#define MSD_OK ((uint8_t)0x00)
#define MSD_ERROR ((uint8_t)0x01)
#define MSD_ERROR_SD_NOT_PRESENT ((uint8_t)0x02)
#define SD_PRESENT ((uint8_t)0x01)
#define SD_NOT_PRESENT ((uint8_t)0x00)
#define SD_DATATIMEOUT ((uint32_t)100000000)
#define SD_DETECT_GPIO_PORT GPIOC
#define SD_DETECT_PIN GPIO_PIN_13
/* Structure(s) -----------------------------------------------------------------------------------------------------*/
typedef enum
{
// SD specific error defines
SD_CMD_CRC_FAIL = (1), // Command response received (but CRC check failed)
SD_DATA_CRC_FAIL = (2), // Data block sent/received (CRC check failed)
SD_CMD_RSP_TIMEOUT = (3), // Command response TimeOut
SD_DATA_TIMEOUT = (4), // Data TimeOut
SD_TX_UNDERRUN = (5), // Transmit FIFO underrun
SD_RX_OVERRUN = (6), // Receive FIFO overrun
SD_START_BIT_ERR = (7), // Start bit not detected on all data signals in wide bus mode
SD_CMD_OUT_OF_RANGE = (8), // Command's argument was out of range.
SD_ADDR_MISALIGNED = (9), // Misaligned address
SD_BLOCK_LEN_ERR = (10), // Transferred block length is not allowed for the card or the number of transferred bytes does not match the block length
SD_ERASE_SEQ_ERR = (11), // An error in the sequence of erase command occurs.
SD_BAD_ERASE_PARAM = (12), // An invalid selection for erase groups
SD_WRITE_PROT_VIOLATION = (13), // Attempt to program a write protect block
SD_LOCK_UNLOCK_FAILED = (14), // Sequence or password error has been detected in unlock command or if there was an attempt to access a locked card
SD_COM_CRC_FAILED = (15), // CRC check of the previous command failed
SD_ILLEGAL_CMD = (16), // Command is not legal for the card state
SD_CARD_ECC_FAILED = (17), // Card internal ECC was applied but failed to correct the data
SD_CC_ERROR = (18), // Internal card controller error
SD_GENERAL_UNKNOWN_ERROR = (19), // General or unknown error
SD_STREAM_READ_UNDERRUN = (20), // The card could not sustain data transfer in stream read operation.
SD_STREAM_WRITE_OVERRUN = (21), // The card could not sustain data programming in stream mode
SD_CID_CSD_OVERWRITE = (22), // CID/CSD overwrite error
SD_WP_ERASE_SKIP = (23), // Only partial address space was erased
SD_CARD_ECC_DISABLED = (24), // Command has been executed without using internal ECC
SD_ERASE_RESET = (25), // Erase sequence was cleared before executing because an out of erase sequence command was received
SD_AKE_SEQ_ERROR = (26), // Error in sequence of authentication.
SD_INVALID_VOLTRANGE = (27),
SD_ADDR_OUT_OF_RANGE = (28),
SD_SWITCH_ERROR = (29),
SD_SDMMC_DISABLED = (30),
SD_SDMMC_FUNCTION_BUSY = (31),
SD_SDMMC_FUNCTION_FAILED = (32),
SD_SDMMC_UNKNOWN_FUNCTION = (33),
SD_OUT_OF_BOUND = (34),
// Standard error defines
SD_INTERNAL_ERROR = (35),
SD_NOT_CONFIGURED = (36),
SD_REQUEST_PENDING = (37),
SD_REQUEST_NOT_APPLICABLE = (38),
SD_INVALID_PARAMETER = (39),
SD_UNSUPPORTED_FEATURE = (40),
SD_UNSUPPORTED_HW = (41),
SD_ERROR = (42),
SD_BUSY = (43),
SD_OK = (0)
} SD_Error_t;
typedef struct
{
uint8_t DAT_BUS_WIDTH; // Shows the currently defined data bus width
uint8_t SECURED_MODE; // Card is in secured mode of operation
uint16_t SD_CARD_TYPE; // Carries information about card type
uint32_t SIZE_OF_PROTECTED_AREA; // Carries information about the capacity of protected area
uint8_t SPEED_CLASS; // Carries information about the speed class of the card
uint8_t PERFORMANCE_MOVE; // Carries information about the card's performance move
uint8_t AU_SIZE; // Carries information about the card's allocation unit size
uint16_t ERASE_SIZE; // Determines the number of AUs to be erased in one operation
uint8_t ERASE_TIMEOUT; // Determines the TimeOut for any number of AU erase
uint8_t ERASE_OFFSET; // Carries information about the erase offset
} SD_CardStatus_t;
typedef struct
{
uint8_t CSDStruct; // CSD structure
uint8_t SysSpecVersion; // System specification version
uint8_t Reserved1; // Reserved
uint8_t TAAC; // Data read access time 1
uint8_t NSAC; // Data read access time 2 in CLK cycles
uint8_t MaxBusClkFrec; // Max. bus clock frequency
uint16_t CardComdClasses; // Card command classes
uint8_t RdBlockLen; // Max. read data block length
uint8_t PartBlockRead; // Partial blocks for read allowed
uint8_t WrBlockMisalign; // Write block misalignment
uint8_t RdBlockMisalign; // Read block misalignment
uint8_t DSRImpl; // DSR implemented
uint8_t Reserved2; // Reserved
uint32_t DeviceSize; // Device Size
uint8_t MaxRdCurrentVDDMin; // Max. read current @ VDD min
uint8_t MaxRdCurrentVDDMax; // Max. read current @ VDD max
uint8_t MaxWrCurrentVDDMin; // Max. write current @ VDD min
uint8_t MaxWrCurrentVDDMax; // Max. write current @ VDD max
uint8_t DeviceSizeMul; // Device size multiplier
uint8_t EraseGrSize; // Erase group size
uint8_t EraseGrMul; // Erase group size multiplier
uint8_t WrProtectGrSize; // Write protect group size
uint8_t WrProtectGrEnable; // Write protect group enable
uint8_t ManDeflECC; // Manufacturer default ECC
uint8_t WrSpeedFact; // Write speed factor
uint8_t MaxWrBlockLen; // Max. write data block length
uint8_t WriteBlockPaPartial; // Partial blocks for write allowed
uint8_t Reserved3; // Reserved
uint8_t ContentProtectAppli; // Content protection application
uint8_t FileFormatGrouop; // File format group
uint8_t CopyFlag; // Copy flag (OTP)
uint8_t PermWrProtect; // Permanent write protection
uint8_t TempWrProtect; // Temporary write protection
uint8_t FileFormat; // File format
uint8_t ECC; // ECC code
uint8_t CSD_CRC; // CSD CRC
uint8_t Reserved4; // Always 1
} SD_CSD_t;
typedef struct
{
uint8_t ManufacturerID; // Manufacturer ID
uint16_t OEM_AppliID; // OEM/Application ID
uint32_t ProdName1; // Product Name part1
uint8_t ProdName2; // Product Name part2
uint8_t ProdRev; // Product Revision
uint32_t ProdSN; // Product Serial Number
uint8_t Reserved1; // Reserved1
uint16_t ManufactDate; // Manufacturing Date
uint8_t CID_CRC; // CID CRC
uint8_t Reserved2; // Always 1
} SD_CID_t;
typedef enum
{
SD_STD_CAPACITY_V1_1 = 0,
SD_STD_CAPACITY_V2_0 = 1,
SD_HIGH_CAPACITY = 2,
SD_MULTIMEDIA = 3,
SD_SECURE_DIGITAL_IO = 4,
SD_HIGH_SPEED_MULTIMEDIA = 5,
SD_SECURE_DIGITAL_IO_COMBO = 6,
SD_HIGH_CAPACITY_MMC = 7,
} SD_CardType_t;
typedef struct
{
volatile SD_CSD_t SD_csd; // SD card specific data register
volatile SD_CID_t SD_cid; // SD card identification number register
uint64_t CardCapacity; // Card capacity
uint32_t CardBlockSize; // Card block size
} SD_CardInfo_t;
/* Prototype(s) -----------------------------------------------------------------------------------------------------*/
extern SD_CardInfo_t SD_CardInfo;
extern SD_CardType_t SD_CardType;
void SD_Initialize_LL (DMA_Stream_TypeDef *dma);
bool SD_Init (void);
bool SD_IsDetected (void);
bool SD_GetState (void);
SD_Error_t SD_GetCardInfo (void);
SD_Error_t SD_ReadBlocks_DMA (uint64_t ReadAddress, uint32_t *buffer, uint32_t BlockSize, uint32_t NumberOfBlocks);
SD_Error_t SD_CheckRead (void);
SD_Error_t SD_WriteBlocks_DMA (uint64_t WriteAddress, uint32_t *buffer, uint32_t BlockSize, uint32_t NumberOfBlocks);
SD_Error_t SD_CheckWrite (void);
SD_Error_t SD_Erase (uint64_t StartAddress, uint64_t EndAddress);
SD_Error_t SD_GetCardStatus (SD_CardStatus_t* pCardStatus);
/* ------------------------------------------------------------------------------------------------------------------*/
#endif // __fatfs_sd_sdio_H__

View file

@ -42,7 +42,7 @@
#include "drivers/light_led.h"
#include "drivers/nvic.h"
#include "drivers/persistent.h"
#include "drivers/sdmmc_sdio.h"
#include "drivers/sdcard/sdmmc_sdio.h"
#include "drivers/time.h"
#include "drivers/usb_msc.h"

View file

@ -372,9 +372,8 @@ void init(void)
updateHardwareRevision();
#endif
#if defined(USE_SDCARD_SDIO) && defined(STM32H7)
#if defined(USE_SDCARD_SDIO) && (defined(STM32H7) || defined(STM32F7))
sdioPinConfigure();
SDIO_GPIO_Init();
#endif
#ifdef USE_USB_MSC

View file

@ -213,8 +213,9 @@ static int8_t STORAGE_Read (uint8_t lun,
UNUSED(lun);
LED1_ON;
for (int i = 0; i < blk_len; i++) {
while (sdcard_readBlock(blk_addr + i, buf + (512 * i), NULL, 0) == 0);
while (sdcard_poll() == 0);
while (sdcard_readBlock(blk_addr + i, buf + (512 * i), NULL, 0) == 0)
sdcard_poll();
while (sdcard_poll() == 0);
}
LED1_OFF;
return 0;

View file

@ -1,289 +0,0 @@
/**
******************************************************************************
* @file usbd_storage_template.c
* @author MCD Application Team
* @version V1.2.0
* @date 09-November-2015
* @brief Memory management layer
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include <stdio.h>
#include <stdbool.h>
#include "platform.h"
#include "drivers/sdmmc_sdio.h"
#include "drivers/light_led.h"
#include "drivers/io.h"
#include "common/utils.h"
#ifdef USE_HAL_DRIVER
#include "usbd_msc.h"
#else
#include "usbd_msc_mem.h"
#include "usbd_msc_core.h"
#endif
#include "usbd_storage.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Extern function prototypes ------------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/* USB NVIC Priority has to be lower than both DMA and SDIO priority,
* otherwise SDIO won't be able to preempt USB.
*/
#define STORAGE_LUN_NBR 1
#define STORAGE_BLK_NBR 0x10000
#define STORAGE_BLK_SIZ 0x200
static int8_t STORAGE_Init (uint8_t lun);
#ifdef USE_HAL_DRIVER
static int8_t STORAGE_GetCapacity (uint8_t lun,
uint32_t *block_num,
uint16_t *block_size);
#else
static int8_t STORAGE_GetCapacity (uint8_t lun,
uint32_t *block_num,
uint32_t *block_size);
#endif
static int8_t STORAGE_IsReady (uint8_t lun);
static int8_t STORAGE_IsWriteProtected (uint8_t lun);
static int8_t STORAGE_Read (uint8_t lun,
uint8_t *buf,
uint32_t blk_addr,
uint16_t blk_len);
static int8_t STORAGE_Write (uint8_t lun,
uint8_t *buf,
uint32_t blk_addr,
uint16_t blk_len);
static int8_t STORAGE_GetMaxLun (void);
/* USB Mass storage Standard Inquiry Data */
static uint8_t STORAGE_Inquirydata[] = {//36
/* LUN 0 */
0x00,
0x80,
0x02,
0x02,
#ifdef USE_HAL_DRIVER
(STANDARD_INQUIRY_DATA_LEN - 5),
#else
(USBD_STD_INQUIRY_LENGTH - 5),
#endif
0x00,
0x00,
0x00,
'S', 'T', 'M', ' ', ' ', ' ', ' ', ' ', /* Manufacturer : 8 bytes */
'P', 'r', 'o', 'd', 'u', 't', ' ', ' ', /* Product : 16 Bytes */
' ', ' ', ' ', ' ', ' ', ' ', ' ', ' ',
'0', '.', '0' ,'1', /* Version : 4 Bytes */
};
#ifdef USE_HAL_DRIVER
USBD_StorageTypeDef USBD_MSC_MICRO_SDIO_fops =
{
STORAGE_Init,
STORAGE_GetCapacity,
STORAGE_IsReady,
STORAGE_IsWriteProtected,
STORAGE_Read,
STORAGE_Write,
STORAGE_GetMaxLun,
(int8_t*)STORAGE_Inquirydata,
};
#else
USBD_STORAGE_cb_TypeDef USBD_MSC_MICRO_SDIO_fops =
{
STORAGE_Init,
STORAGE_GetCapacity,
STORAGE_IsReady,
STORAGE_IsWriteProtected,
STORAGE_Read,
STORAGE_Write,
STORAGE_GetMaxLun,
(int8_t*)STORAGE_Inquirydata,
};
#endif
/*******************************************************************************
* Function Name : Read_Memory
* Description : Handle the Read operation from the microSD card.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
static int8_t STORAGE_Init (uint8_t lun)
{
//Initialize SD_DET
#ifdef SDCARD_DETECT_PIN
const IO_t sd_det = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN));
IOInit(sd_det, OWNER_SDCARD_DETECT, 0);
IOConfigGPIO(sd_det, IOCFG_IPU);
#endif
UNUSED(lun);
LED0_OFF;
#if defined(STM32H7) // H7 uses IDMA
SD_Initialize_LL(0);
#else
SD_Initialize_LL(SDIO_DMA);
#endif
if (SD_Init() != 0) return 1;
LED0_ON;
return 0;
}
/*******************************************************************************
* Function Name : Read_Memory
* Description : Handle the Read operation from the STORAGE card.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
#ifdef USE_HAL_DRIVER
static int8_t STORAGE_GetCapacity (uint8_t lun, uint32_t *block_num, uint16_t *block_size)
#else
static int8_t STORAGE_GetCapacity (uint8_t lun, uint32_t *block_num, uint32_t *block_size)
#endif
{
UNUSED(lun);
if (SD_IsDetected() == 0) {
return -1;
}
SD_GetCardInfo();
*block_num = SD_CardInfo.CardCapacity;
*block_size = 512;
return (0);
}
/*******************************************************************************
* Function Name : Read_Memory
* Description : Handle the Read operation from the STORAGE card.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
static int8_t STORAGE_IsReady (uint8_t lun)
{
UNUSED(lun);
int8_t ret = -1;
if (SD_GetState() == true && SD_IsDetected() == SD_PRESENT) {
ret = 0;
}
return ret;
}
/*******************************************************************************
* Function Name : Read_Memory
* Description : Handle the Read operation from the STORAGE card.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
static int8_t STORAGE_IsWriteProtected (uint8_t lun)
{
UNUSED(lun);
return 0;
}
/*******************************************************************************
* Function Name : Read_Memory
* Description : Handle the Read operation from the STORAGE card.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
static int8_t STORAGE_Read (uint8_t lun,
uint8_t *buf,
uint32_t blk_addr,
uint16_t blk_len)
{
UNUSED(lun);
if (SD_IsDetected() == 0) {
return -1;
}
LED1_ON;
//buf should be 32bit aligned, but usually is so we don't do byte alignment
if (SD_ReadBlocks_DMA(blk_addr, (uint32_t*) buf, 512, blk_len) == 0) {
while (SD_CheckRead());
while(SD_GetState() == false);
LED1_OFF;
return 0;
}
LED1_OFF;
return -1;
}
/*******************************************************************************
* Function Name : Write_Memory
* Description : Handle the Write operation to the STORAGE card.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
static int8_t STORAGE_Write (uint8_t lun,
uint8_t *buf,
uint32_t blk_addr,
uint16_t blk_len)
{
UNUSED(lun);
if (SD_IsDetected() == 0) {
return -1;
}
LED1_ON;
//buf should be 32bit aligned, but usually is so we don't do byte alignment
if (SD_WriteBlocks_DMA(blk_addr, (uint32_t*) buf, 512, blk_len) == 0) {
while (SD_CheckWrite());
while(SD_GetState() == false);
LED1_OFF;
return 0;
}
LED1_OFF;
return -1;
}
/*******************************************************************************
* Function Name : Write_Memory
* Description : Handle the Write operation to the STORAGE card.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
static int8_t STORAGE_GetMaxLun (void)
{
return (STORAGE_LUN_NBR - 1);
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -169,6 +169,7 @@
#define USE_SDCARD_SDIO
#define SDCARD_SDIO_DMA DMA_TAG(2,3,4)
#define SDCARD_SDIO_4BIT
#define SDCARD_SDIO_DEVICE SDIODEV_1
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
// *************** ADC *****************************

View file

@ -71,7 +71,7 @@
/* #define HAL_RNG_MODULE_ENABLED */
#define HAL_RTC_MODULE_ENABLED
/* #define HAL_SAI_MODULE_ENABLED */
/* #define HAL_SD_MODULE_ENABLED */
#define HAL_SD_MODULE_ENABLED
/* #define HAL_MMC_MODULE_ENABLED */
/* #define HAL_SPDIFRX_MODULE_ENABLED */
#define HAL_SPI_MODULE_ENABLED