diff --git a/cmake/stm32f7.cmake b/cmake/stm32f7.cmake
index 6aa2a9fd802..62819928d56 100644
--- a/cmake/stm32f7.cmake
+++ b/cmake/stm32f7.cmake
@@ -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
diff --git a/cmake/stm32h7.cmake b/cmake/stm32h7.cmake
index 81a8b2d889d..34e26f409b1 100644
--- a/cmake/stm32h7.cmake
+++ b/cmake/stm32h7.cmake
@@ -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
diff --git a/src/main/drivers/sdcard/sdcard_sdio.c b/src/main/drivers/sdcard/sdcard_sdio.c
index 38e36811cc3..9914719fb75 100644
--- a/src/main/drivers/sdcard/sdcard_sdio.c
+++ b/src/main/drivers/sdcard/sdcard_sdio.c
@@ -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;
diff --git a/src/main/drivers/sdcard/sdmmc_sdio.h b/src/main/drivers/sdcard/sdmmc_sdio.h
index f488d334f96..4c4e60ca35c 100644
--- a/src/main/drivers/sdcard/sdmmc_sdio.h
+++ b/src/main/drivers/sdcard/sdmmc_sdio.h
@@ -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);
diff --git a/src/main/drivers/sdcard/sdmmc_sdio_f4xx.c b/src/main/drivers/sdcard/sdmmc_sdio_f4xx.c
index 592ce4cf641..8999cdd7197 100644
--- a/src/main/drivers/sdcard/sdmmc_sdio_f4xx.c
+++ b/src/main/drivers/sdcard/sdmmc_sdio_f4xx.c
@@ -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;
diff --git a/src/main/drivers/sdcard/sdmmc_sdio_f7xx.c b/src/main/drivers/sdcard/sdmmc_sdio_f7xx.c
deleted file mode 100644
index 20fe8ca8dd0..00000000000
--- a/src/main/drivers/sdcard/sdmmc_sdio_f7xx.c
+++ /dev/null
@@ -1,1603 +0,0 @@
-/*
- * This file is part of INAV, Cleanflight and Betaflight.
- *
- * INAV, 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 .
- */
-
-/*
- * Original author: Alain (https://github.com/aroyer-qc)
- * Modified for BF source: Chris Hockuba (https://github.com/conkerkh)
- * Modified for INAV: Konstantin (https://github.com/digitalentity)
- */
-
-/* Include(s) -------------------------------------------------------------------------------------------------------*/
-
-#include "stdbool.h"
-#include
-
-#include "platform.h"
-
-#ifdef USE_SDCARD_SDIO
-
-#include "sdmmc_sdio.h"
-#include "stm32f7xx.h"
-
-#include "drivers/io.h"
-#include "drivers/io_impl.h"
-#include "drivers/nvic.h"
-#include "drivers/time.h"
-#include "drivers/rcc.h"
-#include "drivers/dma.h"
-
-#include "build/debug.h"
-
-
-/* Define(s) --------------------------------------------------------------------------------------------------------*/
-
-//#define DMA_CHANNEL_4 ((uint32_t)0x08000000)
-#define DMA_MEMORY_TO_PERIPH ((uint32_t)DMA_SxCR_DIR_0)
-
-//#define DMA_PERIPH_TO_MEMORY ((uint32_t)0x00)
-#define DMA_MINC_ENABLE ((uint32_t)DMA_SxCR_MINC)
-#define DMA_MDATAALIGN_WORD ((uint32_t)DMA_SxCR_MSIZE_1)
-#define DMA_PDATAALIGN_WORD ((uint32_t)DMA_SxCR_PSIZE_1)
-#define DMA_PRIORITY_LOW ((uint32_t)0x00000000U)
-#define DMA_PRIORITY_MEDIUM ((uint32_t)DMA_SxCR_PL_0)
-#define DMA_PRIORITY_HIGH ((uint32_t)DMA_SxCR_PL_1)
-#define DMA_PRIORITY_VERY_HIGH ((uint32_t)DMA_SxCR_PL)
-#define DMA_MBURST_INC4 ((uint32_t)DMA_SxCR_MBURST_0)
-#define DMA_PBURST_INC4 ((uint32_t)DMA_SxCR_PBURST_0)
-
-#define BLOCK_SIZE ((uint32_t)(512))
-
-#define IFCR_CLEAR_MASK_STREAM3 (DMA_LIFCR_CTCIF3 | DMA_LIFCR_CHTIF3 | DMA_LIFCR_CTEIF3 | DMA_LIFCR_CDMEIF3 | DMA_LIFCR_CFEIF3)
-#define IFCR_CLEAR_MASK_STREAM6 (DMA_HIFCR_CTCIF6 | DMA_HIFCR_CHTIF6 | DMA_HIFCR_CTEIF6 | DMA_HIFCR_CDMEIF6 | DMA_HIFCR_CFEIF6)
-
-#define SDMMC_ICR_STATIC_FLAGS ((uint32_t)(SDMMC_ICR_CCRCFAILC | SDMMC_ICR_DCRCFAILC | SDMMC_ICR_CTIMEOUTC |\
- SDMMC_ICR_DTIMEOUTC | SDMMC_ICR_TXUNDERRC | SDMMC_ICR_RXOVERRC |\
- SDMMC_ICR_CMDRENDC | SDMMC_ICR_CMDSENTC | SDMMC_ICR_DATAENDC |\
- SDMMC_ICR_DBCKENDC))
-
-#define SD_SOFTWARE_COMMAND_TIMEOUT ((uint32_t)0x00020000)
-
-#define SD_OCR_ADDR_OUT_OF_RANGE ((uint32_t)0x80000000)
-#define SD_OCR_ADDR_MISALIGNED ((uint32_t)0x40000000)
-#define SD_OCR_BLOCK_LEN_ERR ((uint32_t)0x20000000)
-#define SD_OCR_ERASE_SEQ_ERR ((uint32_t)0x10000000)
-#define SD_OCR_BAD_ERASE_PARAM ((uint32_t)0x08000000)
-#define SD_OCR_WRITE_PROT_VIOLATION ((uint32_t)0x04000000)
-#define SD_OCR_LOCK_UNLOCK_FAILED ((uint32_t)0x01000000)
-#define SD_OCR_COM_CRC_FAILED ((uint32_t)0x00800000)
-#define SD_OCR_ILLEGAL_CMD ((uint32_t)0x00400000)
-#define SD_OCR_CARD_ECC_FAILED ((uint32_t)0x00200000)
-#define SD_OCR_CC_ERROR ((uint32_t)0x00100000)
-#define SD_OCR_GENERAL_UNKNOWN_ERROR ((uint32_t)0x00080000)
-#define SD_OCR_STREAM_READ_UNDERRUN ((uint32_t)0x00040000)
-#define SD_OCR_STREAM_WRITE_OVERRUN ((uint32_t)0x00020000)
-#define SD_OCR_CID_CSD_OVERWRITE ((uint32_t)0x00010000)
-#define SD_OCR_WP_ERASE_SKIP ((uint32_t)0x00008000)
-#define SD_OCR_CARD_ECC_DISABLED ((uint32_t)0x00004000)
-#define SD_OCR_ERASE_RESET ((uint32_t)0x00002000)
-#define SD_OCR_AKE_SEQ_ERROR ((uint32_t)0x00000008)
-#define SD_OCR_ERRORBITS ((uint32_t)0xFDFFE008)
-
-#define SD_R6_GENERAL_UNKNOWN_ERROR ((uint32_t)0x00002000)
-#define SD_R6_ILLEGAL_CMD ((uint32_t)0x00004000)
-#define SD_R6_COM_CRC_FAILED ((uint32_t)0x00008000)
-
-#define SD_VOLTAGE_WINDOW_SD ((uint32_t)0x80100000)
-#define SD_RESP_HIGH_CAPACITY ((uint32_t)0x40000000)
-#define SD_RESP_STD_CAPACITY ((uint32_t)0x00000000)
-#define SD_CHECK_PATTERN ((uint32_t)0x000001AA)
-
-#define SD_MAX_VOLT_TRIAL ((uint32_t)0x0000FFFF)
-#define SD_ALLZERO ((uint32_t)0x00000000)
-
-#define SD_WIDE_BUS_SUPPORT ((uint32_t)0x00040000)
-#define SD_SINGLE_BUS_SUPPORT ((uint32_t)0x00010000)
-#define SD_CARD_LOCKED ((uint32_t)0x02000000)
-
-#define SD_0TO7BITS ((uint32_t)0x000000FF)
-#define SD_8TO15BITS ((uint32_t)0x0000FF00)
-#define SD_16TO23BITS ((uint32_t)0x00FF0000)
-#define SD_24TO31BITS ((uint32_t)0xFF000000)
-#define SD_MAX_DATA_LENGTH ((uint32_t)0x01FFFFFF)
-
-#define SD_CCCC_ERASE ((uint32_t)0x00000020)
-
-#define SD_SDMMC_SEND_IF_COND ((uint32_t)SD_CMD_HS_SEND_EXT_CSD)
-
-
-
-#define SD_BUS_WIDE_1B ((uint32_t)0x00000000)
-#define SD_BUS_WIDE_4B SDMMC_CLKCR_WIDBUS_0
-#define SD_BUS_WIDE_8B SDMMC_CLKCR_WIDBUS_1
-
-#define SD_CMD_RESPONSE_SHORT SDMMC_CMD_WAITRESP_0
-#define SD_CMD_RESPONSE_LONG SDMMC_CMD_WAITRESP
-
-#define SD_DATABLOCK_SIZE_8B (SDMMC_DCTRL_DBLOCKSIZE_0|SDMMC_DCTRL_DBLOCKSIZE_1)
-#define SD_DATABLOCK_SIZE_64B (SDMMC_DCTRL_DBLOCKSIZE_1|SDMMC_DCTRL_DBLOCKSIZE_2)
-#define SD_DATABLOCK_SIZE_512B (SDMMC_DCTRL_DBLOCKSIZE_0|SDMMC_DCTRL_DBLOCKSIZE_3)
-
-#define CLKCR_CLEAR_MASK ((uint32_t)(SDMMC_CLKCR_CLKDIV | SDMMC_CLKCR_PWRSAV |\
- SDMMC_CLKCR_BYPASS | SDMMC_CLKCR_WIDBUS |\
- SDMMC_CLKCR_NEGEDGE | SDMMC_CLKCR_HWFC_EN))
-
-#define DCTRL_CLEAR_MASK ((uint32_t)(SDMMC_DCTRL_DTEN | SDMMC_DCTRL_DTDIR |\
- SDMMC_DCTRL_DTMODE | SDMMC_DCTRL_DBLOCKSIZE))
-
-#define CMD_CLEAR_MASK ((uint32_t)(SDMMC_CMD_CMDINDEX | SDMMC_CMD_WAITRESP |\
- SDMMC_CMD_WAITINT | SDMMC_CMD_WAITPEND |\
- SDMMC_CMD_CPSMEN | SDMMC_CMD_SDMMC1SUSPEND))
-
-#define SDMMC_INIT_CLK_DIV ((uint8_t)0x76)
-#define SDMMC_CLK_DIV ((uint8_t)0x00)
-
-
-#define SD_CMD_GO_IDLE_STATE ((uint8_t)0) // Resets the SD memory card.
-#define SD_CMD_SEND_OP_COND ((uint8_t)1) // Sends host capacity support information and activates the card's initialization process.
-#define SD_CMD_ALL_SEND_CID ((uint8_t)2) // Asks any card connected to the host to send the CID numbers on the CMD line.
-#define SD_CMD_SET_REL_ADDR ((uint8_t)3) // Asks the card to publish a new relative address (RCA).
-#define SD_CMD_HS_SWITCH ((uint8_t)6) // Checks switchable function (mode 0) and switch card function (mode 1).
-#define SD_CMD_SEL_DESEL_CARD ((uint8_t)7) // Selects the card by its own relative address and gets deselected by any other address
-#define SD_CMD_HS_SEND_EXT_CSD ((uint8_t)8) // Sends SD Memory Card interface condition, which includes host supply voltage information
- // and asks the card whether card supports voltage.
-#define SD_CMD_SEND_CSD ((uint8_t)9) // Addressed card sends its card specific data (CSD) on the CMD line.
-#define SD_CMD_SEND_CID ((uint8_t)10) // Addressed card sends its card identification (CID) on the CMD line.
-#define SD_CMD_STOP_TRANSMISSION ((uint8_t)12) // Forces the card to stop transmission.
-#define SD_CMD_SEND_STATUS ((uint8_t)13) // Addressed card sends its status register.
-#define SD_CMD_SET_BLOCKLEN ((uint8_t)16) // Sets the block length (in bytes for SDSC) for all following block commands
- // (read, write, lock). Default block length is fixed to 512 Bytes. Not effective
- // for SDHS and SDXC.
-#define SD_CMD_READ_SINGLE_BLOCK ((uint8_t)17) // Reads single block of size selected by SET_BLOCKLEN in case of SDSC, and a block of
- // fixed 512 bytes in case of SDHC and SDXC.
-#define SD_CMD_READ_MULT_BLOCK ((uint8_t)18) // Continuously transfers data blocks from card to host until interrupted by
- // STOP_TRANSMISSION command.
-#define SD_CMD_WRITE_SINGLE_BLOCK ((uint8_t)24) // Writes single block of size selected by SET_BLOCKLEN in case of SDSC, and a block of
- // fixed 512 bytes in case of SDHC and SDXC.
-#define SD_CMD_WRITE_MULT_BLOCK ((uint8_t)25) // Continuously writes blocks of data until a STOP_TRANSMISSION follows.
-#define SD_CMD_SD_ERASE_GRP_START ((uint8_t)32) // Sets the address of the first write block to be erased. (For SD card only).
-#define SD_CMD_SD_ERASE_GRP_END ((uint8_t)33) // Sets the address of the last write block of the continuous range to be erased.
- // system set by switch function command (CMD6).
-#define SD_CMD_ERASE ((uint8_t)38) // Reserved for SD security applications.
-#define SD_CMD_FAST_IO ((uint8_t)39) // SD card doesn't support it (Reserved).
-#define SD_CMD_APP_CMD ((uint8_t)55) // Indicates to the card that the next command is an application specific command rather
- // than a standard command.
-
-/* Following commands are SD Card Specific commands.
- SDMMC_APP_CMD should be sent before sending these commands. */
-#define SD_CMD_APP_SD_SET_BUSWIDTH ((uint8_t)6) // (ACMD6) Defines the data bus width to be used for data transfer. The allowed data bus
- // widths are given in SCR register.
-#define SD_CMD_SD_APP_STATUS ((uint8_t)13) // (ACMD13) Sends the SD status.
-#define SD_CMD_SD_APP_OP_COND ((uint8_t)41) // (ACMD41) Sends host capacity support information (HCS) and asks the accessed card to
- // send its operating condition register (OCR) content in the response on the CMD line.
-#define SD_CMD_SD_APP_SEND_SCR ((uint8_t)51) // Reads the SD Configuration Register (SCR).
-
-#define SDMMC_DIR_TX 1
-#define SDMMC_DIR_RX 0
-
-#define SDMMC_DMA_ST3 1
-
-
-/* Typedef(s) -------------------------------------------------------------------------------------------------------*/
-
-typedef enum
-{
- SD_SINGLE_BLOCK = 0, // Single block operation
- SD_MULTIPLE_BLOCK = 1, // Multiple blocks operation
-} SD_Operation_t;
-
-typedef struct
-{
- uint32_t CSD[4]; // SD card specific data table
- uint32_t CID[4]; // SD card identification number table
- volatile uint32_t TransferComplete; // SD transfer complete flag in non blocking mode
- volatile uint32_t TransferError; // SD transfer error flag in non blocking mode
- volatile uint32_t RXCplt; // SD RX Complete is equal 0 when no transfer
- volatile uint32_t TXCplt; // SD TX Complete is equal 0 when no transfer
- volatile uint32_t Operation; // SD transfer operation (read/write)
-} SD_Handle_t;
-
-typedef enum
-{
- SD_CARD_READY = ((uint32_t)0x00000001), // Card state is ready
- SD_CARD_IDENTIFICATION = ((uint32_t)0x00000002), // Card is in identification state
- SD_CARD_STANDBY = ((uint32_t)0x00000003), // Card is in standby state
- SD_CARD_TRANSFER = ((uint32_t)0x00000004), // Card is in transfer state
- SD_CARD_SENDING = ((uint32_t)0x00000005), // Card is sending an operation
- SD_CARD_RECEIVING = ((uint32_t)0x00000006), // Card is receiving operation information
- SD_CARD_PROGRAMMING = ((uint32_t)0x00000007), // Card is in programming state
- SD_CARD_DISCONNECTED = ((uint32_t)0x00000008), // Card is disconnected
- SD_CARD_ERROR = ((uint32_t)0x000000FF) // Card is in error state
-} SD_CardState_t;
-
-/* Variable(s) ------------------------------------------------------------------------------------------------------*/
-
-static SD_Handle_t SD_Handle;
-SD_CardInfo_t SD_CardInfo;
-static uint32_t SD_Status;
-static uint32_t SD_CardRCA;
-SD_CardType_t SD_CardType;
-static volatile uint32_t TimeOut;
-DMA_Stream_TypeDef *dma_stream;
-
-/* Private function(s) ----------------------------------------------------------------------------------------------*/
-
-static void SD_DataTransferInit (uint32_t Size, uint32_t DataBlockSize, bool IsItReadFromCard);
-static SD_Error_t SD_TransmitCommand (uint32_t Command, uint32_t Argument, int8_t ResponseType);
-static SD_Error_t SD_CmdResponse (uint8_t SD_CMD, int8_t ResponseType);
-static void SD_GetResponse (uint32_t* pResponse);
-static SD_Error_t CheckOCR_Response (uint32_t Response_R1);
-static void SD_DMA_Complete (DMA_Stream_TypeDef* pDMA_Stream);
-static SD_Error_t SD_InitializeCard (void);
-
-static SD_Error_t SD_PowerON (void);
-static SD_Error_t SD_WideBusOperationConfig (uint32_t WideMode);
-static SD_Error_t SD_FindSCR (uint32_t *pSCR);
-
-void SDMMC_DMA_ST3_IRQHandler(dmaChannelDescriptor_t *dma);
-void SDMMC_DMA_ST6_IRQHandler(dmaChannelDescriptor_t *dma);
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-/** DataTransferInit
- *
- * @brief Prepare the state machine for transfer
- * @param SD_TransferType_e TransfertDir
- * @param SD_CARD_BlockSize_e Size
- */
-static void SD_DataTransferInit(uint32_t Size, uint32_t DataBlockSize, bool IsItReadFromCard)
-{
- uint32_t Direction;
-
- SDMMC1->DTIMER = SD_DATATIMEOUT; // Set the SDMMC1 Data TimeOut value
- SDMMC1->DLEN = Size; // Set the SDMMC1 DataLength value
- Direction = (IsItReadFromCard == true) ? SDMMC_DCTRL_DTDIR : 0;
- SDMMC1->DCTRL |= (uint32_t)(DataBlockSize | Direction | SDMMC_DCTRL_DTEN | 0x01);
- return;
-}
-
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-/** SD_TransmitCommand
- *
- * @brief Send the commande to SDMMC1
- * @param uint32_t Command
- * @param uint32_t Argument Must provide the response size
- * @param uint8_t ResponseType
- * @retval SD Card error state
- */
-static SD_Error_t SD_TransmitCommand(uint32_t Command, uint32_t Argument, int8_t ResponseType)
-{
- SD_Error_t ErrorState;
-
- WRITE_REG(SDMMC1->ICR, SDMMC_ICR_STATIC_FLAGS); // Clear the Command Flags
- WRITE_REG(SDMMC1->ARG, (uint32_t)Argument); // Set the SDMMC1 Argument value
- WRITE_REG(SDMMC1->CMD, (uint32_t)(Command | SDMMC_CMD_CPSMEN)); // Set SDMMC1 command parameters
-
- if ((Argument == 0) && (ResponseType == 0)) {
- ResponseType = -1; // Go idle command
- }
-
- ErrorState = SD_CmdResponse(Command & SDMMC_CMD_CMDINDEX, ResponseType);
- WRITE_REG(SDMMC1->ICR, SDMMC_ICR_STATIC_FLAGS); // Clear the Command Flags
-
- return ErrorState;
-}
-
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-/**
- * @brief Checks for error conditions for any response.
- * - R2 (CID or CSD) response.
- * - R3 (OCR) response.
- *
- * @param SD_CMD: The sent command Index
- * @retval SD Card error state
- */
-static SD_Error_t SD_CmdResponse(uint8_t SD_CMD, int8_t ResponseType)
-{
- uint32_t Response_R1;
- uint32_t TimeOut;
- uint32_t Flag;
-
- if (ResponseType == -1) {
- Flag = SDMMC_STA_CMDSENT;
- }
- else {
- Flag = SDMMC_STA_CCRCFAIL | SDMMC_STA_CMDREND | SDMMC_STA_CTIMEOUT;
- }
-
- TimeOut = SD_SOFTWARE_COMMAND_TIMEOUT;
- do {
- SD_Status = SDMMC1->STA;
- TimeOut--;
- } while (((SD_Status & Flag) == 0) && (TimeOut > 0));
-
- if (ResponseType <= 0) {
- if (TimeOut == 0){
- return SD_CMD_RSP_TIMEOUT;
- }
- else {
- return SD_OK;
- }
- }
-
- if ((SDMMC1->STA & SDMMC_STA_CTIMEOUT) != 0) {
- return SD_CMD_RSP_TIMEOUT;
- }
- if (ResponseType == 3) {
- if (TimeOut == 0) {
- return SD_CMD_RSP_TIMEOUT; // Card is not V2.0 compliant or card does not support the set voltage range
- }
- else {
- return SD_OK; // Card is SD V2.0 compliant
- }
- }
-
- if ((SDMMC1->STA & SDMMC_STA_CCRCFAIL) != 0) {
- return SD_CMD_CRC_FAIL;
- }
- if (ResponseType == 2) {
- return SD_OK;
- }
- if ((uint8_t)SDMMC1->RESPCMD != SD_CMD) {
- return SD_ILLEGAL_CMD; // Check if response is of desired command
- }
-
- Response_R1 = SDMMC1->RESP1; // We have received response, retrieve it for analysis
-
- if (ResponseType == 1) {
- return CheckOCR_Response(Response_R1);
- }
- else if (ResponseType == 6) {
- if ((Response_R1 & (SD_R6_GENERAL_UNKNOWN_ERROR | SD_R6_ILLEGAL_CMD | SD_R6_COM_CRC_FAILED)) == SD_ALLZERO) {
- SD_CardRCA = Response_R1;
- }
- if ((Response_R1 & SD_R6_GENERAL_UNKNOWN_ERROR) == SD_R6_GENERAL_UNKNOWN_ERROR) {
- return SD_GENERAL_UNKNOWN_ERROR;
- }
- if ((Response_R1 & SD_R6_ILLEGAL_CMD) == SD_R6_ILLEGAL_CMD) {
- return SD_ILLEGAL_CMD;
- }
- if ((Response_R1 & SD_R6_COM_CRC_FAILED) == SD_R6_COM_CRC_FAILED) {
- return SD_COM_CRC_FAILED;
- }
- }
-
- return SD_OK;
-}
-
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-/**
- * @brief Analyze the OCR response and return the appropriate error code
- * @param Response_R1: OCR Response code
- * @retval SD Card error state
- */
-static SD_Error_t CheckOCR_Response(uint32_t Response_R1)
-{
- if ((Response_R1 & SD_OCR_ERRORBITS) == SD_ALLZERO) return SD_OK;
- if ((Response_R1 & SD_OCR_ADDR_OUT_OF_RANGE) == SD_OCR_ADDR_OUT_OF_RANGE) return SD_ADDR_OUT_OF_RANGE;
- if ((Response_R1 & SD_OCR_ADDR_MISALIGNED) == SD_OCR_ADDR_MISALIGNED) return SD_ADDR_MISALIGNED;
- if ((Response_R1 & SD_OCR_BLOCK_LEN_ERR) == SD_OCR_BLOCK_LEN_ERR) return SD_BLOCK_LEN_ERR;
- if ((Response_R1 & SD_OCR_ERASE_SEQ_ERR) == SD_OCR_ERASE_SEQ_ERR) return SD_ERASE_SEQ_ERR;
- if ((Response_R1 & SD_OCR_BAD_ERASE_PARAM) == SD_OCR_BAD_ERASE_PARAM) return SD_BAD_ERASE_PARAM;
- if ((Response_R1 & SD_OCR_WRITE_PROT_VIOLATION) == SD_OCR_WRITE_PROT_VIOLATION) return SD_WRITE_PROT_VIOLATION;
- if ((Response_R1 & SD_OCR_LOCK_UNLOCK_FAILED) == SD_OCR_LOCK_UNLOCK_FAILED) return SD_LOCK_UNLOCK_FAILED;
- if ((Response_R1 & SD_OCR_COM_CRC_FAILED) == SD_OCR_COM_CRC_FAILED) return SD_COM_CRC_FAILED;
- if ((Response_R1 & SD_OCR_ILLEGAL_CMD) == SD_OCR_ILLEGAL_CMD) return SD_ILLEGAL_CMD;
- if ((Response_R1 & SD_OCR_CARD_ECC_FAILED) == SD_OCR_CARD_ECC_FAILED) return SD_CARD_ECC_FAILED;
- if ((Response_R1 & SD_OCR_CC_ERROR) == SD_OCR_CC_ERROR) return SD_CC_ERROR;
- if ((Response_R1 & SD_OCR_GENERAL_UNKNOWN_ERROR) == SD_OCR_GENERAL_UNKNOWN_ERROR)return SD_GENERAL_UNKNOWN_ERROR;
- if ((Response_R1 & SD_OCR_STREAM_READ_UNDERRUN) == SD_OCR_STREAM_READ_UNDERRUN) return SD_STREAM_READ_UNDERRUN;
- if ((Response_R1 & SD_OCR_STREAM_WRITE_OVERRUN) == SD_OCR_STREAM_WRITE_OVERRUN) return SD_STREAM_WRITE_OVERRUN;
- if ((Response_R1 & SD_OCR_CID_CSD_OVERWRITE) == SD_OCR_CID_CSD_OVERWRITE) return SD_CID_CSD_OVERWRITE;
- if ((Response_R1 & SD_OCR_WP_ERASE_SKIP) == SD_OCR_WP_ERASE_SKIP) return SD_WP_ERASE_SKIP;
- if ((Response_R1 & SD_OCR_CARD_ECC_DISABLED) == SD_OCR_CARD_ECC_DISABLED) return SD_CARD_ECC_DISABLED;
- if ((Response_R1 & SD_OCR_ERASE_RESET) == SD_OCR_ERASE_RESET) return SD_ERASE_RESET;
- if ((Response_R1 & SD_OCR_AKE_SEQ_ERROR) == SD_OCR_AKE_SEQ_ERROR) return SD_AKE_SEQ_ERROR;
-
- return SD_OK;
-}
-
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-/** GetResponse
- *
- * @brief Get response from SD device
- * @param uint32_t* pResponse
- */
-static void SD_GetResponse(uint32_t* pResponse)
-{
- pResponse[0] = SDMMC1->RESP1;
- pResponse[1] = SDMMC1->RESP2;
- pResponse[2] = SDMMC1->RESP3;
- pResponse[3] = SDMMC1->RESP4;
-}
-
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-/**
- * @brief SD DMA transfer complete RX and TX callback.
- * @param DMA_Stream_TypeDef* pDMA_Stream
- */
-static void SD_DMA_Complete(DMA_Stream_TypeDef* pDMA_Stream)
-{
- if (SD_Handle.RXCplt) {
- if (SD_Handle.Operation == ((SDMMC_DIR_RX << 1) | SD_MULTIPLE_BLOCK)) {
- /* Send stop command in multiblock write */
- SD_TransmitCommand((SD_CMD_STOP_TRANSMISSION | SD_CMD_RESPONSE_SHORT), 0, 1);
- }
-
- /* Disable the DMA transfer for transmit request by setting the DMAEN bit
- in the SD DCTRL register */
- SDMMC1->DCTRL &= (uint32_t)~((uint32_t)SDMMC_DCTRL_DMAEN);
-
- /* Clear all the static flags */
- SDMMC1->ICR = SDMMC_ICR_STATIC_FLAGS;
-
- /* Clear flag */
- SD_Handle.RXCplt = 0;
-
- /* Disable the stream */
- pDMA_Stream->CR &= ~DMA_SxCR_EN;
- }
- else {
- /* Enable Dataend IE */
- SDMMC1->MASK |= SDMMC_MASK_DATAENDIE;
- }
-}
-
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-/**
- * @brief Initializes all cards or single card as the case may be Card(s) come
- * into standby state.
- * @retval SD Card error state
- */
-static SD_Error_t SD_InitializeCard(void)
-{
- SD_Error_t ErrorState = SD_OK;
-
- if ((SDMMC1->POWER & SDMMC_POWER_PWRCTRL) != 0) { // Power off
- if (SD_CardType != SD_SECURE_DIGITAL_IO) {
- // Send CMD2 ALL_SEND_CID
- if ((ErrorState = SD_TransmitCommand((SD_CMD_ALL_SEND_CID | SD_CMD_RESPONSE_LONG), 0, 2)) != SD_OK) {
- return ErrorState;
- }
-
- // Get Card identification number data
- SD_GetResponse(SD_Handle.CID);
- }
-
- if ((SD_CardType == SD_STD_CAPACITY_V1_1) || (SD_CardType == SD_STD_CAPACITY_V2_0) ||
- (SD_CardType == SD_SECURE_DIGITAL_IO_COMBO) || (SD_CardType == SD_HIGH_CAPACITY)) {
- // Send CMD3 SET_REL_ADDR with argument 0
- // SD Card publishes its RCA.
- if ((ErrorState = SD_TransmitCommand((SD_CMD_SET_REL_ADDR | SD_CMD_RESPONSE_SHORT), 0, 6)) != SD_OK) {
- return ErrorState;
- }
- }
-
- if (SD_CardType != SD_SECURE_DIGITAL_IO) {
- // Send CMD9 SEND_CSD with argument as card's RCA
- if ((ErrorState = SD_TransmitCommand((SD_CMD_SEND_CSD | SD_CMD_RESPONSE_LONG), SD_CardRCA, 2)) == SD_OK) {
- // Get Card Specific Data
- SD_GetResponse(SD_Handle.CSD);
- }
- }
- }
- else {
- ErrorState = SD_REQUEST_NOT_APPLICABLE;
- }
-
- return ErrorState;
-}
-
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-/**
- * @brief Prepre the DMA transfer
- * @param pDMA: DMA Stream to use for the DMA operation
- * @param pBuffer: Pointer to the buffer that will contain the data to transmit
- * @param BlockSize: The SD card Data block size
- * @note BlockSize must be 512 bytes.
- * @param NumberOfBlocks: Number of blocks to write
- * @retval SD Card error state
- */
-static void SD_StartBlockTransfert(uint32_t* pBuffer, uint32_t BlockSize, uint32_t NumberOfBlocks, uint8_t dir)
-{
- DMA_Stream_TypeDef *pDMA = dma_stream;
-
- SDMMC1->DCTRL = 0; // Initialize data control register
- SD_Handle.TransferComplete = 0; // Initialize handle flags
- SD_Handle.TransferError = SD_OK;
- SD_Handle.Operation = (NumberOfBlocks > 1) ? SD_MULTIPLE_BLOCK : SD_SINGLE_BLOCK; // Initialize SD Read operation
- SD_Handle.Operation |= dir << 1;
- SDMMC1->MASK = 0;
-
- if (dir == SDMMC_DIR_RX) {
- SDMMC1->MASK |= (SDMMC_MASK_DCRCFAILIE | SDMMC_MASK_DTIMEOUTIE | // Enable transfer interrupts
- SDMMC_MASK_DATAENDIE | SDMMC_MASK_RXOVERRIE);
- }
- else {
- SDMMC1->MASK |= (SDMMC_MASK_DCRCFAILIE | SDMMC_MASK_DTIMEOUTIE | // Enable transfer interrupts
- SDMMC_MASK_TXUNDERRIE);
- }
-
- if (dir == SDMMC_DIR_TX) {
- SDMMC1->DCTRL |= SDMMC_DCTRL_DMAEN; // Enable SDMMC1 DMA transfer
- }
-
- pDMA->CR &= ~DMA_SxCR_EN; // Disable the Peripheral
- while (pDMA->CR & DMA_SxCR_EN);
-
- pDMA->NDTR = (uint32_t) (BlockSize * NumberOfBlocks) / 4; // Configure DMA Stream data length
- pDMA->M0AR = (uint32_t) pBuffer; // Configure DMA Stream memory address
-
- if (dir == SDMMC_DIR_RX) {
- pDMA->CR &= ~(0x01U << 6U); // Sets peripheral to memory
- }
- else {
- pDMA->CR |= DMA_MEMORY_TO_PERIPH; // Sets memory to peripheral
- }
-
- // Clear the transfer error flag
- if (dma_stream == DMA2_Stream3) {
- DMA2->LIFCR = DMA_LIFCR_CTEIF3 | DMA_LIFCR_CDMEIF3 | DMA_LIFCR_CFEIF3 | DMA_LIFCR_CHTIF3 | DMA_LIFCR_CTCIF3;
- }
- else {
- DMA2->HIFCR = DMA_HIFCR_CTEIF6 | DMA_HIFCR_CDMEIF6 | DMA_HIFCR_CFEIF6 | DMA_HIFCR_CHTIF6 | DMA_HIFCR_CTCIF6;
- }
-
- pDMA->CR |= DMA_SxCR_TCIE | DMA_SxCR_HTIE | DMA_SxCR_TEIE | DMA_SxCR_DMEIE; // Enable all interrupts
- pDMA->FCR |= DMA_SxFCR_FEIE;
- pDMA->CR |= DMA_SxCR_EN; // Enable the Peripheral
-
- if (dir == SDMMC_DIR_RX) {
- SDMMC1->DCTRL |= SDMMC_DCTRL_DMAEN; // Enable SDMMC1 DMA transfer
- }
-}
-
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-/**
- * @brief Reads block(s) from a specified address in a card. The Data transfer
- * is managed by DMA mode.
- * @note This API should be followed by the function SD_CheckOperation()
- * to check the completion of the read process
- * @param pReadBuffer: Pointer to the buffer that will contain the received data
- * @param ReadAddr: Address from where data is to be read
- * @param BlockSize: SD card Data block size
- * @note BlockSize must be 512 bytes.
- * @param NumberOfBlocks: Number of blocks to read.
- * @retval SD Card error state
- */
-SD_Error_t SD_ReadBlocks_DMA(uint64_t ReadAddress, uint32_t *buffer, uint32_t BlockSize, uint32_t NumberOfBlocks)
-{
- SD_Error_t ErrorState;
- uint32_t CmdIndex;
- SD_Handle.RXCplt = 1;
-
- //printf("Reading at %ld into %p %ld blocks\n", (uint32_t)ReadAddress, (void*)buffer, NumberOfBlocks);
-
- if (SD_CardType != SD_HIGH_CAPACITY) {
- ReadAddress *= 512;
- }
-
- SD_StartBlockTransfert(buffer, BlockSize, NumberOfBlocks, SDMMC_DIR_RX);
-
- // Configure the SD DPSM (Data Path State Machine)
- SD_DataTransferInit(BlockSize * NumberOfBlocks, SD_DATABLOCK_SIZE_512B, true);
-
- // Set Block Size for Card
- ErrorState = SD_TransmitCommand((SD_CMD_SET_BLOCKLEN | SD_CMD_RESPONSE_SHORT), BlockSize, 1);
-
- // Send CMD18 READ_MULT_BLOCK with argument data address
- // or send CMD17 READ_SINGLE_BLOCK depending on number of block
- uint8_t retries = 10;
- CmdIndex = (NumberOfBlocks > 1) ? SD_CMD_READ_MULT_BLOCK : SD_CMD_READ_SINGLE_BLOCK;
-
- do {
- ErrorState = SD_TransmitCommand((CmdIndex | SD_CMD_RESPONSE_SHORT), (uint32_t)ReadAddress, 1);
- if (ErrorState != SD_OK && retries--) {
- ErrorState = SD_TransmitCommand((SD_CMD_APP_CMD | SD_CMD_RESPONSE_SHORT), 0, 1);
- }
- } while (ErrorState != SD_OK && retries);
-
- if (ErrorState != SD_OK) {
- SD_Handle.RXCplt = 0;
- }
-
- // Update the SD transfer error in SD handle
- SD_Handle.TransferError = ErrorState;
-
- return ErrorState;
-}
-
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-/**
- * @brief Writes block(s) to a specified address in a card. The Data transfer
- * is managed by DMA mode.
- * @note This API should be followed by the function SD_CheckOperation()
- * to check the completion of the write process (by SD current status polling).
- * @param pWriteBuffer: pointer to the buffer that will contain the data to transmit
- * @param WriteAddress: Address from where data is to be read
- * @param BlockSize: the SD card Data block size
- * @note BlockSize must be 512 bytes.
- * @param NumberOfBlocks: Number of blocks to write
- * @retval SD Card error state
- */
-SD_Error_t SD_WriteBlocks_DMA(uint64_t WriteAddress, uint32_t *buffer, uint32_t BlockSize, uint32_t NumberOfBlocks)
-{
- SD_Error_t ErrorState;
- uint32_t CmdIndex;
- SD_Handle.TXCplt = 1;
-
- if (SD_CardType != SD_HIGH_CAPACITY) {
- WriteAddress *= 512;
- }
-
- // Check number of blocks command
- // Send CMD24 WRITE_SINGLE_BLOCK
- // Send CMD25 WRITE_MULT_BLOCK with argument data address
- CmdIndex = (NumberOfBlocks > 1) ? SD_CMD_WRITE_MULT_BLOCK : SD_CMD_WRITE_SINGLE_BLOCK;
-
- // Set Block Size for Card
- uint8_t retries = 10;
- do {
- ErrorState = SD_TransmitCommand((CmdIndex | SD_CMD_RESPONSE_SHORT), (uint32_t)WriteAddress, 1);
- if (ErrorState != SD_OK && retries--) {
- ErrorState = SD_TransmitCommand((SD_CMD_APP_CMD | SD_CMD_RESPONSE_SHORT), 0, 1);
- }
- } while (ErrorState != SD_OK && retries);
-
- if (ErrorState != SD_OK) {
- SD_Handle.TXCplt = 0;
- return ErrorState;
- }
-
- SD_StartBlockTransfert(buffer, BlockSize, NumberOfBlocks, SDMMC_DIR_TX);
-
- // Configure the SD DPSM (Data Path State Machine)
- SD_DataTransferInit(BlockSize * NumberOfBlocks, SD_DATABLOCK_SIZE_512B, false);
-
- SD_Handle.TransferError = ErrorState;
-
- return ErrorState;
-}
-
-SD_Error_t SD_CheckWrite(void)
-{
- if (SD_Handle.TXCplt != 0) return SD_BUSY;
- return SD_OK;
-}
-
-SD_Error_t SD_CheckRead(void)
-{
- if (SD_Handle.RXCplt != 0) return SD_BUSY;
- return SD_OK;
-}
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-/**
- * @brief Returns information about specific card.
- * contains all SD cardinformation
- * @retval SD Card error state
- */
-SD_Error_t SD_GetCardInfo(void)
-{
- SD_Error_t ErrorState = SD_OK;
- uint32_t Temp = 0;
-
- // Byte 0
- Temp = (SD_Handle.CSD[0] & 0xFF000000) >> 24;
- SD_CardInfo.SD_csd.CSDStruct = (uint8_t)((Temp & 0xC0) >> 6);
- SD_CardInfo.SD_csd.SysSpecVersion = (uint8_t)((Temp & 0x3C) >> 2);
- SD_CardInfo.SD_csd.Reserved1 = Temp & 0x03;
-
- // Byte 1
- Temp = (SD_Handle.CSD[0] & 0x00FF0000) >> 16;
- SD_CardInfo.SD_csd.TAAC = (uint8_t)Temp;
-
- // Byte 2
- Temp = (SD_Handle.CSD[0] & 0x0000FF00) >> 8;
- SD_CardInfo.SD_csd.NSAC = (uint8_t)Temp;
-
- // Byte 3
- Temp = SD_Handle.CSD[0] & 0x000000FF;
- SD_CardInfo.SD_csd.MaxBusClkFrec = (uint8_t)Temp;
-
- // Byte 4
- Temp = (SD_Handle.CSD[1] & 0xFF000000) >> 24;
- SD_CardInfo.SD_csd.CardComdClasses = (uint16_t)(Temp << 4);
-
- // Byte 5
- Temp = (SD_Handle.CSD[1] & 0x00FF0000) >> 16;
- SD_CardInfo.SD_csd.CardComdClasses |= (uint16_t)((Temp & 0xF0) >> 4);
- SD_CardInfo.SD_csd.RdBlockLen = (uint8_t)(Temp & 0x0F);
-
- // Byte 6
- Temp = (SD_Handle.CSD[1] & 0x0000FF00) >> 8;
- SD_CardInfo.SD_csd.PartBlockRead = (uint8_t)((Temp & 0x80) >> 7);
- SD_CardInfo.SD_csd.WrBlockMisalign = (uint8_t)((Temp & 0x40) >> 6);
- SD_CardInfo.SD_csd.RdBlockMisalign = (uint8_t)((Temp & 0x20) >> 5);
- SD_CardInfo.SD_csd.DSRImpl = (uint8_t)((Temp & 0x10) >> 4);
- SD_CardInfo.SD_csd.Reserved2 = 0; /*!< Reserved */
-
- if ((SD_CardType == SD_STD_CAPACITY_V1_1) || (SD_CardType == SD_STD_CAPACITY_V2_0)) {
- SD_CardInfo.SD_csd.DeviceSize = (Temp & 0x03) << 10;
-
- // Byte 7
- Temp = (uint8_t)(SD_Handle.CSD[1] & 0x000000FF);
- SD_CardInfo.SD_csd.DeviceSize |= (Temp) << 2;
-
- // Byte 8
- Temp = (uint8_t)((SD_Handle.CSD[2] & 0xFF000000) >> 24);
- SD_CardInfo.SD_csd.DeviceSize |= (Temp & 0xC0) >> 6;
-
- SD_CardInfo.SD_csd.MaxRdCurrentVDDMin = (Temp & 0x38) >> 3;
- SD_CardInfo.SD_csd.MaxRdCurrentVDDMax = (Temp & 0x07);
-
- // Byte 9
- Temp = (uint8_t)((SD_Handle.CSD[2] & 0x00FF0000) >> 16);
- SD_CardInfo.SD_csd.MaxWrCurrentVDDMin = (Temp & 0xE0) >> 5;
- SD_CardInfo.SD_csd.MaxWrCurrentVDDMax = (Temp & 0x1C) >> 2;
- SD_CardInfo.SD_csd.DeviceSizeMul = (Temp & 0x03) << 1;
-
- // Byte 10
- Temp = (uint8_t)((SD_Handle.CSD[2] & 0x0000FF00) >> 8);
- SD_CardInfo.SD_csd.DeviceSizeMul |= (Temp & 0x80) >> 7;
-
- SD_CardInfo.CardCapacity = (SD_CardInfo.SD_csd.DeviceSize + 1) ;
- SD_CardInfo.CardCapacity *= (1 << (SD_CardInfo.SD_csd.DeviceSizeMul + 2));
- SD_CardInfo.CardBlockSize = 1 << (SD_CardInfo.SD_csd.RdBlockLen);
- SD_CardInfo.CardCapacity *= SD_CardInfo.CardBlockSize;
- }
- else if (SD_CardType == SD_HIGH_CAPACITY) {
- // Byte 7
- Temp = (uint8_t)(SD_Handle.CSD[1] & 0x000000FF);
- SD_CardInfo.SD_csd.DeviceSize = (Temp & 0x3F) << 16;
-
- // Byte 8
- Temp = (uint8_t)((SD_Handle.CSD[2] & 0xFF000000) >> 24);
-
- SD_CardInfo.SD_csd.DeviceSize |= (Temp << 8);
-
- // Byte 9
- Temp = (uint8_t)((SD_Handle.CSD[2] & 0x00FF0000) >> 16);
-
- SD_CardInfo.SD_csd.DeviceSize |= (Temp);
-
- // Byte 10
- Temp = (uint8_t)((SD_Handle.CSD[2] & 0x0000FF00) >> 8);
-
- SD_CardInfo.CardCapacity = ((uint64_t)SD_CardInfo.SD_csd.DeviceSize + 1) * 1024;
- SD_CardInfo.CardBlockSize = 512;
- }
- else {
- // Not supported card type
- ErrorState = SD_ERROR;
- }
-
- SD_CardInfo.SD_csd.EraseGrSize = (Temp & 0x40) >> 6;
- SD_CardInfo.SD_csd.EraseGrMul = (Temp & 0x3F) << 1;
-
- // Byte 11
- Temp = (uint8_t)(SD_Handle.CSD[2] & 0x000000FF);
- SD_CardInfo.SD_csd.EraseGrMul |= (Temp & 0x80) >> 7;
- SD_CardInfo.SD_csd.WrProtectGrSize = (Temp & 0x7F);
-
- // Byte 12
- Temp = (uint8_t)((SD_Handle.CSD[3] & 0xFF000000) >> 24);
- SD_CardInfo.SD_csd.WrProtectGrEnable = (Temp & 0x80) >> 7;
- SD_CardInfo.SD_csd.ManDeflECC = (Temp & 0x60) >> 5;
- SD_CardInfo.SD_csd.WrSpeedFact = (Temp & 0x1C) >> 2;
- SD_CardInfo.SD_csd.MaxWrBlockLen = (Temp & 0x03) << 2;
-
- // Byte 13
- Temp = (uint8_t)((SD_Handle.CSD[3] & 0x00FF0000) >> 16);
- SD_CardInfo.SD_csd.MaxWrBlockLen |= (Temp & 0xC0) >> 6;
- SD_CardInfo.SD_csd.WriteBlockPaPartial = (Temp & 0x20) >> 5;
- SD_CardInfo.SD_csd.Reserved3 = 0;
- SD_CardInfo.SD_csd.ContentProtectAppli = (Temp & 0x01);
-
- // Byte 14
- Temp = (uint8_t)((SD_Handle.CSD[3] & 0x0000FF00) >> 8);
- SD_CardInfo.SD_csd.FileFormatGrouop = (Temp & 0x80) >> 7;
- SD_CardInfo.SD_csd.CopyFlag = (Temp & 0x40) >> 6;
- SD_CardInfo.SD_csd.PermWrProtect = (Temp & 0x20) >> 5;
- SD_CardInfo.SD_csd.TempWrProtect = (Temp & 0x10) >> 4;
- SD_CardInfo.SD_csd.FileFormat = (Temp & 0x0C) >> 2;
- SD_CardInfo.SD_csd.ECC = (Temp & 0x03);
-
- // Byte 15
- Temp = (uint8_t)(SD_Handle.CSD[3] & 0x000000FF);
- SD_CardInfo.SD_csd.CSD_CRC = (Temp & 0xFE) >> 1;
- SD_CardInfo.SD_csd.Reserved4 = 1;
-
- // Byte 0
- Temp = (uint8_t)((SD_Handle.CID[0] & 0xFF000000) >> 24);
- SD_CardInfo.SD_cid.ManufacturerID = Temp;
-
- // Byte 1
- Temp = (uint8_t)((SD_Handle.CID[0] & 0x00FF0000) >> 16);
- SD_CardInfo.SD_cid.OEM_AppliID = Temp << 8;
-
- // Byte 2
- Temp = (uint8_t)((SD_Handle.CID[0] & 0x000000FF00) >> 8);
- SD_CardInfo.SD_cid.OEM_AppliID |= Temp;
-
- // Byte 3
- Temp = (uint8_t)(SD_Handle.CID[0] & 0x000000FF);
- SD_CardInfo.SD_cid.ProdName1 = Temp << 24;
-
- // Byte 4
- Temp = (uint8_t)((SD_Handle.CID[1] & 0xFF000000) >> 24);
- SD_CardInfo.SD_cid.ProdName1 |= Temp << 16;
-
- // Byte 5
- Temp = (uint8_t)((SD_Handle.CID[1] & 0x00FF0000) >> 16);
- SD_CardInfo.SD_cid.ProdName1 |= Temp << 8;
-
- // Byte 6
- Temp = (uint8_t)((SD_Handle.CID[1] & 0x0000FF00) >> 8);
- SD_CardInfo.SD_cid.ProdName1 |= Temp;
-
- // Byte 7
- Temp = (uint8_t)(SD_Handle.CID[1] & 0x000000FF);
- SD_CardInfo.SD_cid.ProdName2 = Temp;
-
- // Byte 8
- Temp = (uint8_t)((SD_Handle.CID[2] & 0xFF000000) >> 24);
- SD_CardInfo.SD_cid.ProdRev = Temp;
-
- // Byte 9
- Temp = (uint8_t)((SD_Handle.CID[2] & 0x00FF0000) >> 16);
- SD_CardInfo.SD_cid.ProdSN = Temp << 24;
-
- // Byte 10
- Temp = (uint8_t)((SD_Handle.CID[2] & 0x0000FF00) >> 8);
- SD_CardInfo.SD_cid.ProdSN |= Temp << 16;
-
- // Byte 11
- Temp = (uint8_t)(SD_Handle.CID[2] & 0x000000FF);
- SD_CardInfo.SD_cid.ProdSN |= Temp << 8;
-
- // Byte 12
- Temp = (uint8_t)((SD_Handle.CID[3] & 0xFF000000) >> 24);
- SD_CardInfo.SD_cid.ProdSN |= Temp;
-
- // Byte 13
- Temp = (uint8_t)((SD_Handle.CID[3] & 0x00FF0000) >> 16);
- SD_CardInfo.SD_cid.Reserved1 |= (Temp & 0xF0) >> 4;
- SD_CardInfo.SD_cid.ManufactDate = (Temp & 0x0F) << 8;
-
- // Byte 14
- Temp = (uint8_t)((SD_Handle.CID[3] & 0x0000FF00) >> 8);
- SD_CardInfo.SD_cid.ManufactDate |= Temp;
-
- // Byte 15
- Temp = (uint8_t)(SD_Handle.CID[3] & 0x000000FF);
- SD_CardInfo.SD_cid.CID_CRC = (Temp & 0xFE) >> 1;
- SD_CardInfo.SD_cid.Reserved2 = 1;
-
- return ErrorState;
-}
-
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-/**
- * @brief Enables wide bus operation for the requested card if supported by
- * card.
- * @param WideMode: Specifies the SD card wide bus mode
- * This parameter can be one of the following values:
- * @arg SD_BUS_WIDE_8B: 8-bit data transfer (Only for MMC)
- * @arg SD_BUS_WIDE_4B: 4-bit data transfer
- * @arg SD_BUS_WIDE_1B: 1-bit data transfer
- * @retval SD Card error state
- */
-static SD_Error_t SD_WideBusOperationConfig(uint32_t WideMode)
-{
- SD_Error_t ErrorState = SD_OK;
- uint32_t Temp;
- uint32_t SCR[2] = {0, 0};
-
- if ((SD_CardType == SD_STD_CAPACITY_V1_1) || (SD_CardType == SD_STD_CAPACITY_V2_0) || (SD_CardType == SD_HIGH_CAPACITY)) {
- if (WideMode == SD_BUS_WIDE_8B) {
- ErrorState = SD_UNSUPPORTED_FEATURE;
- }
- else if ((WideMode == SD_BUS_WIDE_4B) || (WideMode == SD_BUS_WIDE_1B)) {
- if ((SDMMC1->RESP1 & SD_CARD_LOCKED) != SD_CARD_LOCKED) {
- // Get SCR Register
- ErrorState = SD_FindSCR(SCR);
-
- if (ErrorState == SD_OK) {
- Temp = (WideMode == SD_BUS_WIDE_4B) ? SD_WIDE_BUS_SUPPORT : SD_SINGLE_BUS_SUPPORT;
-
- // If requested card supports wide bus operation
- if ((SCR[1] & Temp) != SD_ALLZERO) {
- // Send CMD55 APP_CMD with argument as card's RCA.
- ErrorState = SD_TransmitCommand((SD_CMD_APP_CMD | SD_CMD_RESPONSE_SHORT), SD_CardRCA, 1);
- if (ErrorState == SD_OK) {
- Temp = (WideMode == SD_BUS_WIDE_4B) ? 2 : 0;
-
- // Send ACMD6 APP_CMD with argument as 2 for wide bus mode
- ErrorState = SD_TransmitCommand((SD_CMD_APP_SD_SET_BUSWIDTH | SD_CMD_RESPONSE_SHORT), Temp, 1);
- }
- }
- else {
- ErrorState = SD_REQUEST_NOT_APPLICABLE;
- }
- }
- }
- else {
- ErrorState = SD_LOCK_UNLOCK_FAILED;
- }
- }
- else {
- ErrorState = SD_INVALID_PARAMETER; // WideMode is not a valid argument
- }
-
- if (ErrorState == SD_OK) {
- // Configure the SDMMC1 peripheral, we need this delay for some reason...
- while ((READ_REG(SDMMC1->CLKCR) & 0x800) != WideMode) {
- MODIFY_REG(SDMMC1->CLKCR, CLKCR_CLEAR_MASK, (uint32_t) WideMode);
- }
- }
- }
- else {
- ErrorState = SD_UNSUPPORTED_FEATURE;
- }
-
-
- return ErrorState;
-}
-
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-/**
- * @brief Gets the current card's data status.
- * @retval Data Transfer state
- */
-SD_Error_t SD_GetStatus(void)
-{
- SD_Error_t ErrorState;
- uint32_t Response1;
- SD_CardState_t CardState;
-
-
- // Send Status command
- if ((ErrorState = SD_TransmitCommand((SD_CMD_SEND_STATUS | SD_CMD_RESPONSE_SHORT), SD_CardRCA, 1)) == SD_OK) {
- Response1 = SDMMC1->RESP1;
- CardState = (SD_CardState_t)((Response1 >> 9) & 0x0F);
-
- // Find SD status according to card state
- if (CardState == SD_CARD_TRANSFER) {
- ErrorState = SD_OK;
- }
- else if (CardState == SD_CARD_ERROR) {
- ErrorState = SD_ERROR;
- }
- else {
- ErrorState = SD_BUSY;
- }
- }
- else {
- ErrorState = SD_ERROR;
- }
-
- return ErrorState;
-}
-
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-/**
- * @brief Gets the SD card status.
- * @retval SD Card error state
- */
-SD_Error_t SD_GetCardStatus(SD_CardStatus_t* pCardStatus)
-{
- SD_Error_t ErrorState;
- uint32_t Temp = 0;
- uint32_t Status[16];
- uint32_t Count;
-
- // Check SD response
- if ((SDMMC1->RESP1 & SD_CARD_LOCKED) == SD_CARD_LOCKED) {
- return SD_LOCK_UNLOCK_FAILED;
- }
-
- // Set block size for card if it is not equal to current block size for card
- if ((ErrorState = SD_TransmitCommand((SD_CMD_SET_BLOCKLEN | SD_CMD_RESPONSE_SHORT), 64, 1)) != SD_OK) {
- return ErrorState;
- }
-
- // Send CMD55
- if ((ErrorState = SD_TransmitCommand((SD_CMD_APP_CMD | SD_CMD_RESPONSE_SHORT), SD_CardRCA, 1)) != SD_OK) {
- return ErrorState;
- }
-
- // Configure the SD DPSM (Data Path State Machine)
- SD_DataTransferInit(64, SD_DATABLOCK_SIZE_64B, true);
-
- // Send ACMD13 (SD_APP_STAUS) with argument as card's RCA
- if ((ErrorState = SD_TransmitCommand((SD_CMD_SD_APP_STATUS | SD_CMD_RESPONSE_SHORT), 0, 1)) != SD_OK) {
- return ErrorState;
- }
-
- // Get status data
- while ((SDMMC1->STA & (SDMMC_STA_RXOVERR | SDMMC_STA_DCRCFAIL | SDMMC_STA_DTIMEOUT | SDMMC_STA_DBCKEND)) == 0) {
- if ((SDMMC1->STA & SDMMC_STA_RXFIFOHF) != 0) {
- for(Count = 0; Count < 8; Count++) {
- Status[Count] = SDMMC1->FIFO;
- }
- }
- }
-
- if ((SDMMC1->STA & SDMMC_STA_DTIMEOUT) != 0) {
- return SD_DATA_TIMEOUT;
- }
- else if ((SDMMC1->STA & SDMMC_STA_DCRCFAIL) != 0) {
- return SD_DATA_CRC_FAIL;
- }
- else if ((SDMMC1->STA & SDMMC_STA_RXOVERR) != 0) {
- return SD_RX_OVERRUN;
- }
- else {
- Count = SD_DATATIMEOUT;
- while (((SDMMC1->STA & SDMMC_STA_RXDAVL) != 0) && (Count > 0)) {
- volatile uint8_t tmp = SDMMC1->FIFO;
- (void)tmp;
- Count--;
- }
- }
-
- // Byte 0
- Temp = (Status[0] & 0xC0) >> 6;
- pCardStatus->DAT_BUS_WIDTH = (uint8_t)Temp;
-
- // Byte 0
- Temp = (Status[0] & 0x20) >> 5;
- pCardStatus->SECURED_MODE = (uint8_t)Temp;
-
- // Byte 2
- Temp = (Status[2] & 0xFF);
- pCardStatus->SD_CARD_TYPE = (uint8_t)(Temp << 8);
-
- // Byte 3
- Temp = (Status[3] & 0xFF);
- pCardStatus->SD_CARD_TYPE |= (uint8_t)Temp;
-
- // Byte 4
- Temp = (Status[4] & 0xFF);
- pCardStatus->SIZE_OF_PROTECTED_AREA = (uint8_t)(Temp << 24);
-
- // Byte 5
- Temp = (Status[5] & 0xFF);
- pCardStatus->SIZE_OF_PROTECTED_AREA |= (uint8_t)(Temp << 16);
-
- // Byte 6
- Temp = (Status[6] & 0xFF);
- pCardStatus->SIZE_OF_PROTECTED_AREA |= (uint8_t)(Temp << 8);
-
- // Byte 7
- Temp = (Status[7] & 0xFF);
- pCardStatus->SIZE_OF_PROTECTED_AREA |= (uint8_t)Temp;
-
- // Byte 8
- Temp = (Status[8] & 0xFF);
- pCardStatus->SPEED_CLASS = (uint8_t)Temp;
-
- // Byte 9
- Temp = (Status[9] & 0xFF);
- pCardStatus->PERFORMANCE_MOVE = (uint8_t)Temp;
-
- // Byte 10
- Temp = (Status[10] & 0xF0) >> 4;
- pCardStatus->AU_SIZE = (uint8_t)Temp;
-
- // Byte 11
- Temp = (Status[11] & 0xFF);
- pCardStatus->ERASE_SIZE = (uint8_t)(Temp << 8);
-
- // Byte 12
- Temp = (Status[12] & 0xFF);
- pCardStatus->ERASE_SIZE |= (uint8_t)Temp;
-
- // Byte 13
- Temp = (Status[13] & 0xFC) >> 2;
- pCardStatus->ERASE_TIMEOUT = (uint8_t)Temp;
-
- // Byte 13
- Temp = (Status[13] & 0x3);
- pCardStatus->ERASE_OFFSET = (uint8_t)Temp;
-
- return SD_OK;
-}
-
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-/**
- * @brief Enquires cards about their operating voltage and configures clock
- * controls and stores SD information that will be needed in future
- * in the SD handle.
- * @retval SD Card error state
- */
-static SD_Error_t SD_PowerON(void)
-{
- SD_Error_t ErrorState;
- uint32_t Response;
- uint32_t Count;
- uint32_t ValidVoltage;
- uint32_t SD_Type;
- //uint32_t TickStart;
-
- Count = 0;
- ValidVoltage = 0;
- SD_Type = SD_RESP_STD_CAPACITY;
-
- // Power ON Sequence -------------------------------------------------------
- SDMMC1->CLKCR &= ~SDMMC_CLKCR_CLKEN; // Disable SDMMC1 Clock
- SDMMC1->POWER = SDMMC_POWER_PWRCTRL; // Set Power State to ON
-
- // 1ms: required power up waiting time before starting the SD initialization sequence (make it 2 to be safe)
- delay(2);
-
- SDMMC1->CLKCR |= SDMMC_CLKCR_CLKEN; // Enable SDMMC1 Clock
-
- // CMD0: GO_IDLE_STATE -----------------------------------------------------
- // No CMD response required
- if ((ErrorState = SD_TransmitCommand(SD_CMD_GO_IDLE_STATE, 0, 0)) != SD_OK) {
- // CMD Response Timeout (wait for CMDSENT flag)
- return ErrorState;
- }
-
- // CMD8: SEND_IF_COND ------------------------------------------------------
- // Send CMD8 to verify SD card interface operating condition
- // Argument: - [31:12]: Reserved (shall be set to '0')
- //- [11:8]: Supply Voltage (VHS) 0x1 (Range: 2.7-3.6 V)
- //- [7:0]: Check Pattern (recommended 0xAA)
- // CMD Response: R7 */
- if ((ErrorState = SD_TransmitCommand((SD_SDMMC_SEND_IF_COND | SD_CMD_RESPONSE_SHORT), SD_CHECK_PATTERN, 7)) == SD_OK) {
- // SD Card 2.0
- SD_CardType = SD_STD_CAPACITY_V2_0;
- SD_Type = SD_RESP_HIGH_CAPACITY;
- }
-
- // Send CMD55
- // If ErrorState is Command Timeout, it is a MMC card
- // If ErrorState is SD_OK it is a SD card: SD card 2.0 (voltage range mismatch) or SD card 1.x
- if ((ErrorState = SD_TransmitCommand((SD_CMD_APP_CMD | SD_CMD_RESPONSE_SHORT), 0, 1)) == SD_OK) {
- // SD CARD
- // Send ACMD41 SD_APP_OP_COND with Argument 0x80100000
- while ((ValidVoltage == 0) && (Count < SD_MAX_VOLT_TRIAL)) {
- // SEND CMD55 APP_CMD with RCA as 0
- if ((ErrorState = SD_TransmitCommand((SD_CMD_APP_CMD | SD_CMD_RESPONSE_SHORT), 0, 1)) != SD_OK) {
- return ErrorState;
- }
-
- // Send CMD41
- if ((ErrorState = SD_TransmitCommand((SD_CMD_SD_APP_OP_COND | SD_CMD_RESPONSE_SHORT), SD_VOLTAGE_WINDOW_SD | SD_Type, 3)) != SD_OK) {
- return ErrorState;
- }
-
- Response = SDMMC1->RESP1; // Get command response
- ValidVoltage = (((Response >> 31) == 1) ? 1 : 0); // Get operating voltage
- Count++;
- }
-
- if (Count >= SD_MAX_VOLT_TRIAL) {
- return SD_INVALID_VOLTRANGE;
- }
-
- if ((Response & SD_RESP_HIGH_CAPACITY) == SD_RESP_HIGH_CAPACITY) {
- SD_CardType = SD_HIGH_CAPACITY;
- }
- } // else MMC Card
-
- return ErrorState;
-}
-
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-/**
- * @brief Finds the SD card SCR register value.
- * @param pSCR: pointer to the buffer that will contain the SCR value
- * @retval SD Card error state
- */
-static SD_Error_t SD_FindSCR(uint32_t *pSCR)
-{
- SD_Error_t ErrorState;
- uint32_t Index = 0;
- uint32_t tempscr[2] = {0, 0};
-
- // Set Block Size To 8 Bytes
- // Send CMD55 APP_CMD with argument as card's RCA
- if ((ErrorState = SD_TransmitCommand((SD_CMD_SET_BLOCKLEN | SD_CMD_RESPONSE_SHORT), 8, 1)) == SD_OK) {
- // Send CMD55 APP_CMD with argument as card's RCA
- if ((ErrorState = SD_TransmitCommand((SD_CMD_APP_CMD | SD_CMD_RESPONSE_SHORT), SD_CardRCA, 1)) == SD_OK) {
- SD_DataTransferInit(8, SD_DATABLOCK_SIZE_8B, true);
-
- // Send ACMD51 SD_APP_SEND_SCR with argument as 0
- if ((ErrorState = SD_TransmitCommand((SD_CMD_SD_APP_SEND_SCR | SD_CMD_RESPONSE_SHORT), 0, 1)) == SD_OK) {
- while ((SDMMC1->STA & (SDMMC_STA_RXOVERR | SDMMC_STA_DCRCFAIL | SDMMC_STA_DTIMEOUT | SDMMC_STA_DBCKEND)) == 0) {
- if ((SDMMC1->STA & SDMMC_STA_RXDAVL) != 0) {
- *(tempscr + Index) = SDMMC1->FIFO;
- Index++;
- }
- }
-
- if ((SDMMC1->STA & SDMMC_STA_DTIMEOUT) != 0) {
- ErrorState = SD_DATA_TIMEOUT;
- }
- else if ((SDMMC1->STA & SDMMC_STA_DCRCFAIL) != 0) {
- ErrorState = SD_DATA_CRC_FAIL;
- }
- else if ((SDMMC1->STA & SDMMC_STA_RXOVERR) != 0) {
- ErrorState = SD_RX_OVERRUN;
- }
- else if ((SDMMC1->STA & SDMMC_STA_RXDAVL) != 0) {
- ErrorState = SD_OUT_OF_BOUND;
- }
- else {
- *(pSCR + 1) = ((tempscr[0] & SD_0TO7BITS) << 24) | ((tempscr[0] & SD_8TO15BITS) << 8) |
- ((tempscr[0] & SD_16TO23BITS) >> 8) | ((tempscr[0] & SD_24TO31BITS) >> 24);
-
- *(pSCR) = ((tempscr[1] & SD_0TO7BITS) << 24) | ((tempscr[1] & SD_8TO15BITS) << 8) |
- ((tempscr[1] & SD_16TO23BITS) >> 8) | ((tempscr[1] & SD_24TO31BITS) >> 24);
- }
- }
- }
- }
-
- return ErrorState;
-}
-
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-/**
- * @brief Initialize the SDMMC1 module, DMA, and IO
- */
-bool SD_Initialize_LL(DMA_Stream_TypeDef * dmaRef)
-{
- // 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;
- }
-
- // Reset SDMMC1 Module
- RCC->APB2RSTR |= RCC_APB2RSTR_SDMMC1RST;
- delay(1);
- RCC->APB2RSTR &= ~RCC_APB2RSTR_SDMMC1RST;
- delay(1);
-
- // Enable SDMMC1 clock
- RCC->APB2ENR |= RCC_APB2ENR_SDMMC1EN;
-
- // Enable DMA2 clocks
- RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN;
-
- //Configure Pins
- RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN | RCC_AHB1ENR_GPIODEN;
-
- const IO_t d0 = IOGetByTag(IO_TAG(PC8));
- const IO_t clk = IOGetByTag(IO_TAG(PC12));
- const IO_t cmd = IOGetByTag(IO_TAG(PD2));
-
-#define SDMMC_DATA IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_NOPULL)
-#define SDMMC_CMD IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_NOPULL)
-#define SDMMC_CLK IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_NOPULL)
-
- IOInit(d0, OWNER_SDCARD, RESOURCE_NONE, 0);
- IOConfigGPIOAF(d0, SDMMC_DATA, GPIO_AF12_SDMMC1);
-
-#ifdef SDCARD_SDIO_4BIT
- const IO_t d1 = IOGetByTag(IO_TAG(PC9));
- const IO_t d2 = IOGetByTag(IO_TAG(PC10));
- const IO_t d3 = IOGetByTag(IO_TAG(PC11));
-
- IOInit(d1, OWNER_SDCARD, RESOURCE_NONE, 0);
- IOConfigGPIOAF(d1, SDMMC_DATA, GPIO_AF12_SDMMC1);
-
- IOInit(d2, OWNER_SDCARD, RESOURCE_NONE, 0);
- IOConfigGPIOAF(d2, SDMMC_DATA, GPIO_AF12_SDMMC1);
-
- IOInit(d3, OWNER_SDCARD, RESOURCE_NONE, 0);
- IOConfigGPIOAF(d3, SDMMC_DATA, GPIO_AF12_SDMMC1);
-#endif
-
- IOInit(clk, OWNER_SDCARD, RESOURCE_NONE, 0);
- IOConfigGPIOAF(clk, SDMMC_CLK, GPIO_AF12_SDMMC1);
-
- IOInit(cmd, OWNER_SDCARD, RESOURCE_NONE, 0);
- IOConfigGPIOAF(cmd, SDMMC_CMD, GPIO_AF12_SDMMC1);
-
- // NVIC configuration for SDIO interrupts
- NVIC_SetPriority(SDMMC1_IRQn, NVIC_PRIO_SDIO);
- NVIC_EnableIRQ(SDMMC1_IRQn);
-
- dma_stream = dmaRef;
- RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN;
- if ((uint32_t)dma_stream == (uint32_t)DMA2_Stream3) {
- // Initialize DMA2 channel 3
- DMA2_Stream3->CR = 0; // Reset DMA Stream control register
- DMA2_Stream3->PAR = (uint32_t)&SDMMC1->FIFO;
- DMA2->LIFCR = IFCR_CLEAR_MASK_STREAM3; // Clear all interrupt flags
- DMA2_Stream3->CR = (DMA_CHANNEL_4 | DMA_SxCR_PFCTRL | // Prepare the DMA Stream configuration
- DMA_MINC_ENABLE | DMA_PDATAALIGN_WORD | // And write to DMA Stream CR register
- DMA_MDATAALIGN_WORD | DMA_PRIORITY_VERY_HIGH |
- DMA_MBURST_INC4 | DMA_PBURST_INC4 |
- DMA_MEMORY_TO_PERIPH);
- DMA2_Stream3->FCR = (DMA_SxFCR_DMDIS | DMA_SxFCR_FTH); // Configuration FIFO control register
- dmaInit(dmaGetByRef(DMA2_Stream3), OWNER_SDCARD, 0);
- dmaSetHandler(dmaGetByRef(DMA2_Stream3), SDMMC_DMA_ST3_IRQHandler, 1, 0);
- }
- else {
- // Initialize DMA2 channel 6
- DMA2_Stream6->CR = 0; // Reset DMA Stream control register
- DMA2_Stream6->PAR = (uint32_t)&SDMMC1->FIFO;
- DMA2->HIFCR = IFCR_CLEAR_MASK_STREAM6; // Clear all interrupt flags
- DMA2_Stream6->CR = (DMA_CHANNEL_4 | DMA_SxCR_PFCTRL | // Prepare the DMA Stream configuration
- DMA_MINC_ENABLE | DMA_PDATAALIGN_WORD | // And write to DMA Stream CR register
- DMA_MDATAALIGN_WORD | DMA_PRIORITY_VERY_HIGH |
- DMA_MBURST_INC4 | DMA_PBURST_INC4 |
- DMA_MEMORY_TO_PERIPH);
- DMA2_Stream6->FCR = (DMA_SxFCR_DMDIS | DMA_SxFCR_FTH); // Configuration FIFO control register
- dmaInit(dmaGetByRef(DMA2_Stream6), OWNER_SDCARD, 0);
- dmaSetHandler(dmaGetByRef(DMA2_Stream6), SDMMC_DMA_ST6_IRQHandler, 1, 0);
- }
-
- return true;
-}
-
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-bool SD_GetState(void)
-{
- // Check SDCARD status
- if (SD_GetStatus() == SD_OK) return true;
- return false;
-}
-
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-bool SD_Init(void)
-{
- SD_Error_t ErrorState;
-
- // Initialize SDMMC1 peripheral interface with default configuration for SD card initialization
- MODIFY_REG(SDMMC1->CLKCR, CLKCR_CLEAR_MASK, (uint32_t) SDMMC_INIT_CLK_DIV);
-
- delay(100);
-
- // Identify card operating voltage
- if ((ErrorState = SD_PowerON()) == SD_OK) {
- delay(100);
- // Initialize the present card and put them in idle state
- if ((ErrorState = SD_InitializeCard()) == SD_OK) {
- delay(100);
- // Read CSD/CID MSD registers
- if ((ErrorState = SD_GetCardInfo()) == SD_OK) {
- // Select the Card - Send CMD7 SDMMC_SEL_DESEL_CARD
- ErrorState = SD_TransmitCommand((SD_CMD_SEL_DESEL_CARD | SD_CMD_RESPONSE_SHORT), SD_CardRCA, 1);
- delay(100);
- MODIFY_REG(SDMMC1->CLKCR, CLKCR_CLEAR_MASK, (uint32_t) SDMMC_CLK_DIV); // Configure SDMMC1 peripheral interface
- }
- }
- }
-
- // Configure SD Bus width
- if (ErrorState == SD_OK) {
- delay(100);
- // Enable wide operation
-#ifdef SDCARD_SDIO_4BIT
- ErrorState = SD_WideBusOperationConfig(SD_BUS_WIDE_4B);
-#else
- ErrorState = SD_WideBusOperationConfig(SD_BUS_WIDE_1B);
-#endif
- delay(100);
- }
-
- // Configure the SDCARD device
- return ErrorState;
-}
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-/**
- * @brief This function handles SD card interrupt request.
- */
-void SDMMC1_IRQHandler(void)
-{
- // Check for SDMMC1 interrupt flags
- if ((SDMMC1->STA & SDMMC_STA_DATAEND) != 0) {
- SDMMC1->ICR = SDMMC_ICR_DATAENDC;
- SDMMC1->ICR = SDMMC_ICR_STATIC_FLAGS;
- SDMMC1->MASK &= ~(SDMMC_MASK_DATAENDIE | SDMMC_MASK_DCRCFAILIE | SDMMC_MASK_DTIMEOUTIE |
- SDMMC_MASK_TXUNDERRIE | SDMMC_MASK_RXOVERRIE | SDMMC_MASK_TXFIFOHEIE | SDMMC_MASK_RXFIFOHFIE);
-
- /* Currently doesn't implement multiple block write handling */
- if ((SD_Handle.Operation & 0x02) == (SDMMC_DIR_TX << 1)) {
- /* Disable the stream */
- dma_stream->CR &= ~DMA_SxCR_EN;
- SDMMC1->DCTRL &= ~(SDMMC_DCTRL_DMAEN);
- /* Transfer is complete */
- SD_Handle.TXCplt = 0;
- if ((SD_Handle.Operation & 0x01) == SD_MULTIPLE_BLOCK) {
- /* Send stop command in multiblock write */
- SD_TransmitCommand((SD_CMD_STOP_TRANSMISSION | SD_CMD_RESPONSE_SHORT), 0, 1);
- }
- }
- SD_Handle.TransferComplete = 1;
- SD_Handle.TransferError = SD_OK; // No transfer error
- }
- else if ((SDMMC1->STA & SDMMC_STA_DCRCFAIL) != 0) {
- SD_Handle.TransferError = SD_DATA_CRC_FAIL;
- }
- else if ((SDMMC1->STA & SDMMC_STA_DTIMEOUT) != 0) {
- SD_Handle.TransferError = SD_DATA_TIMEOUT;
- }
- else if ((SDMMC1->STA & SDMMC_STA_RXOVERR) != 0) {
- SD_Handle.TransferError = SD_RX_OVERRUN;
- }
- else if ((SDMMC1->STA & SDMMC_STA_TXUNDERR) != 0) {
- SD_Handle.TransferError = SD_TX_UNDERRUN;
- }
-
- SDMMC1->ICR = SDMMC_ICR_STATIC_FLAGS;
-
- // Disable all SDMMC1 peripheral interrupt sources
- SDMMC1->MASK &= ~(SDMMC_MASK_DCRCFAILIE | SDMMC_MASK_DTIMEOUTIE | SDMMC_MASK_DATAENDIE |
- SDMMC_MASK_TXFIFOHEIE | SDMMC_MASK_RXFIFOHFIE | SDMMC_MASK_TXUNDERRIE |
- SDMMC_MASK_RXOVERRIE);
-}
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-/**
- * @brief This function handles DMA2 Stream 3 interrupt request.
- */
-void SDMMC_DMA_ST3_IRQHandler(dmaChannelDescriptor_t *dma)
-{
- UNUSED(dma);
- // Transfer Error Interrupt management
- if ((DMA2->LISR & DMA_LISR_TEIF3) != 0) {
- if ((DMA2_Stream3->CR & DMA_SxCR_TEIE) != 0) {
- DMA2_Stream3->CR &= ~DMA_SxCR_TEIE; // Disable the transfer error interrupt
- DMA2->LIFCR = DMA_LIFCR_CTEIF3; // Clear the transfer error flag
- }
- }
-
- // FIFO Error Interrupt management
- if ((DMA2->LISR & DMA_LISR_FEIF3) != 0) {
- if ((DMA2_Stream3->FCR & DMA_SxFCR_FEIE) != 0) {
- DMA2_Stream3->FCR &= ~DMA_SxFCR_FEIE; // Disable the FIFO Error interrupt
- DMA2->LIFCR = DMA_LIFCR_CFEIF3; // Clear the FIFO error flag
- }
- }
-
- // Direct Mode Error Interrupt management
- if ((DMA2->LISR & DMA_LISR_DMEIF3) != 0) {
- if ((DMA2_Stream3->CR & DMA_SxCR_DMEIE) != 0) {
- DMA2_Stream3->CR &= ~DMA_SxCR_DMEIE; // Disable the direct mode Error interrupt
- DMA2->LIFCR = DMA_LIFCR_CDMEIF3; // Clear the FIFO error flag
- }
- }
-
- // Half Transfer Complete Interrupt management
- if ((DMA2->LISR & DMA_LISR_HTIF3) != 0) {
- if ((DMA2_Stream3->CR & DMA_SxCR_HTIE) != 0) {
- if (((DMA2_Stream3->CR) & (uint32_t)(DMA_SxCR_DBM)) != 0) { // Multi_Buffering mode enabled
- DMA2->LIFCR = DMA_LIFCR_CHTIF3; // Clear the half transfer complete flag
- }
- else {
- if ((DMA2_Stream3->CR & DMA_SxCR_CIRC) == 0) { // Disable the half transfer interrupt if the DMA mode is not CIRCULAR
- DMA2_Stream3->CR &= ~DMA_SxCR_HTIE; // Disable the half transfer interrupt
- }
-
- DMA2->LIFCR = DMA_LIFCR_CHTIF3; // Clear the half transfer complete flag
- }
- }
- }
-
- // Transfer Complete Interrupt management
- if ((DMA2->LISR & DMA_LISR_TCIF3) != 0) {
- if ((DMA2_Stream3->CR & DMA_SxCR_TCIE) != 0) {
- if ((DMA2_Stream3->CR & (uint32_t)(DMA_SxCR_DBM)) != 0) {
- DMA2->LIFCR = DMA_LIFCR_CTCIF3; // Clear the transfer complete flag
- }
- else {
- if ((DMA2_Stream3->CR & DMA_SxCR_CIRC) == 0) {
- DMA2_Stream3->CR &= ~DMA_SxCR_TCIE; // Disable the transfer complete interrupt
- }
-
- DMA2->LIFCR = DMA_LIFCR_CTCIF3; // Clear the transfer complete flag
- SD_DMA_Complete(DMA2_Stream3);
- }
- }
- }
-}
-
-
-/** -----------------------------------------------------------------------------------------------------------------*/
-/**
- * @brief This function handles DMA2 Stream 6 interrupt request.
- */
-void SDMMC_DMA_ST6_IRQHandler(dmaChannelDescriptor_t *dma)
-{
- UNUSED(dma);
- // Transfer Error Interrupt management
- if ((DMA2->HISR & DMA_HISR_TEIF6) != 0) {
- if ((DMA2_Stream6->CR & DMA_SxCR_TEIE) != 0) {
- DMA2_Stream6->CR &= ~DMA_SxCR_TEIE; // Disable the transfer error interrupt
- DMA2->HIFCR = DMA_HIFCR_CTEIF6; // Clear the transfer error flag
- }
- }
-
- // FIFO Error Interrupt management
- if ((DMA2->HISR & DMA_HISR_FEIF6) != 0) {
- if ((DMA2_Stream6->FCR & DMA_SxFCR_FEIE) != 0) {
- DMA2_Stream6->FCR &= ~DMA_SxFCR_FEIE; // Disable the FIFO Error interrupt
- DMA2->HIFCR = DMA_HIFCR_CFEIF6; // Clear the FIFO error flag
- }
- }
-
- // Direct Mode Error Interrupt management
- if ((DMA2->HISR & DMA_HISR_DMEIF6) != 0) {
- if ((DMA2_Stream6->CR & DMA_SxCR_DMEIE) != 0) {
- DMA2_Stream6->CR &= ~DMA_SxCR_DMEIE; // Disable the direct mode Error interrupt
- DMA2->HIFCR = DMA_HIFCR_CDMEIF6; // Clear the FIFO error flag
- }
- }
-
- // Half Transfer Complete Interrupt management
- if ((DMA2->HISR & DMA_HISR_HTIF6) != 0) {
- if ((DMA2_Stream6->CR & DMA_SxCR_HTIE) != 0) {
- if (((DMA2_Stream6->CR) & (uint32_t)(DMA_SxCR_DBM)) != 0) { // Multi_Buffering mode enabled
- DMA2->HIFCR = DMA_HIFCR_CHTIF6; // Clear the half transfer complete flag
- }
- else {
- if ((DMA2_Stream6->CR & DMA_SxCR_CIRC) == 0) { // Disable the half transfer interrupt if the DMA mode is not CIRCULAR
- DMA2_Stream6->CR &= ~DMA_SxCR_HTIE; // Disable the half transfer interrupt
- }
-
- DMA2->HIFCR = DMA_HIFCR_CHTIF6; // Clear the half transfer complete flag
- }
- }
- }
-
- // Transfer Complete Interrupt management
- if ((DMA2->HISR & DMA_HISR_TCIF6) != 0) {
- if ((DMA2_Stream6->CR & DMA_SxCR_TCIE) != 0) {
- if ((DMA2_Stream6->CR & (uint32_t)(DMA_SxCR_DBM)) != 0) {
- DMA2->HIFCR = DMA_HIFCR_CTCIF6; // Clear the transfer complete flag
- }
- else {
- if ((DMA2_Stream6->CR & DMA_SxCR_CIRC) == 0) {
- DMA2_Stream6->CR &= ~DMA_SxCR_TCIE; // Disable the transfer complete interrupt
- }
-
- DMA2->HIFCR = DMA_HIFCR_CTCIF6; // Clear the transfer complete flag
- SD_DMA_Complete(DMA2_Stream6);
- }
- }
- }
-}
-
-/* ------------------------------------------------------------------------------------------------------------------*/
-#endif
diff --git a/src/main/drivers/sdcard/sdmmc_sdio_h7xx.c b/src/main/drivers/sdcard/sdmmc_sdio_hal.c
similarity index 79%
rename from src/main/drivers/sdcard/sdmmc_sdio_h7xx.c
rename to src/main/drivers/sdcard/sdmmc_sdio_hal.c
index 9a9eafe1b08..a0813bd35d8 100644
--- a/src/main/drivers/sdcard/sdmmc_sdio_h7xx.c
+++ b/src/main/drivers/sdcard/sdmmc_sdio_hal.c
@@ -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);
- HAL_NVIC_EnableIRQ(sdioHardware->irqn);
-}
-
-void SDIO_GPIO_Init(void)
-{
- if (!sdioHardware) {
+#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);
- 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);
+ __HAL_LINKDMA(hsd, hdmarx, sd_dma);
+ __HAL_LINKDMA(hsd, hdmatx, sd_dma);
+#else
+ UNUSED(hsd);
#endif
- IOHi(clk);
- IOHi(cmd);
- IOConfigGPIO(clk, IOCFG_OUT_PP);
- IOConfigGPIO(cmd, IOCFG_OUT_PP);
+ HAL_NVIC_SetPriority(sdioHardware->irqn, 2, 0);
+ HAL_NVIC_EnableIRQ(sdioHardware->irqn);
}
-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;
+ }
+
+#ifdef SDCARD_SDIO_4BIT
+ if (HAL_SD_ConfigWideBusOperation(&hsd, SDMMC_BUS_WIDE_4B) != HAL_OK) {
+ return SD_ERROR;
+ }
+#endif
- switch(hsd1.SdCard.CardType) {
+ 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
diff --git a/src/main/drivers/sdio.h b/src/main/drivers/sdio.h
index 2464e1594dc..d411a17ad12 100644
--- a/src/main/drivers/sdio.h
+++ b/src/main/drivers/sdio.h
@@ -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
diff --git a/src/main/drivers/sdmmc_sdio.h b/src/main/drivers/sdmmc_sdio.h
deleted file mode 100644
index 075768189dd..00000000000
--- a/src/main/drivers/sdmmc_sdio.h
+++ /dev/null
@@ -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 .
- */
-
-/*
- * 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
-
-#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__
diff --git a/src/main/drivers/usb_msc_f4xx.c b/src/main/drivers/usb_msc_f4xx.c
index 8bc9a9ade3e..43fcec9b734 100644
--- a/src/main/drivers/usb_msc_f4xx.c
+++ b/src/main/drivers/usb_msc_f4xx.c
@@ -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"
diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c
index bc84d380a37..413b6914e14 100644
--- a/src/main/fc/fc_init.c
+++ b/src/main/fc/fc_init.c
@@ -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
diff --git a/src/main/msc/usbd_storage_sd_spi.c b/src/main/msc/usbd_storage_sd_spi.c
index 03f53eed72a..4573d156bd8 100644
--- a/src/main/msc/usbd_storage_sd_spi.c
+++ b/src/main/msc/usbd_storage_sd_spi.c
@@ -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;
diff --git a/src/main/msc/usbd_storage_sdio.c b/src/main/msc/usbd_storage_sdio.c
deleted file mode 100644
index 4a262419abd..00000000000
--- a/src/main/msc/usbd_storage_sdio.c
+++ /dev/null
@@ -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
- *
- * © COPYRIGHT 2015 STMicroelectronics
- *
- * 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
-#include
-
-#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****/
diff --git a/src/main/target/MATEKF765/target.h b/src/main/target/MATEKF765/target.h
index 8a726d56b3c..2a75a89cda6 100644
--- a/src/main/target/MATEKF765/target.h
+++ b/src/main/target/MATEKF765/target.h
@@ -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 *****************************
diff --git a/src/main/target/stm32f7xx_hal_conf.h b/src/main/target/stm32f7xx_hal_conf.h
index 8c82cd3b952..7295e934210 100644
--- a/src/main/target/stm32f7xx_hal_conf.h
+++ b/src/main/target/stm32f7xx_hal_conf.h
@@ -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