diff --git a/make/mcu/STM32F3.mk b/make/mcu/STM32F3.mk
index c0d96caace..4b60e91723 100644
--- a/make/mcu/STM32F3.mk
+++ b/make/mcu/STM32F3.mk
@@ -43,7 +43,14 @@ DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC)\
$(USBPERIPH_SRC)
endif
-ifneq ($(filter SDCARD, $(FEATURES)),)
+ifneq ($(filter SDCARD_SPI, $(FEATURES)),)
+INCLUDE_DIRS := $(INCLUDE_DIRS) \
+ $(FATFS_DIR) \
+
+VPATH := $(VPATH):$(FATFS_DIR)
+endif
+
+ifneq ($(filter SDCARD_SDIO, $(FEATURES)),)
INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(FATFS_DIR) \
diff --git a/make/mcu/STM32F4.mk b/make/mcu/STM32F4.mk
index f5bdcd5432..a7abfb7efd 100644
--- a/make/mcu/STM32F4.mk
+++ b/make/mcu/STM32F4.mk
@@ -137,7 +137,13 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(ROOT)/src/main/vcpf4
endif
-ifneq ($(filter SDCARD,$(FEATURES)),)
+ifneq ($(filter SDCARD_SPI,$(FEATURES)),)
+INCLUDE_DIRS := $(INCLUDE_DIRS) \
+ $(FATFS_DIR)
+VPATH := $(VPATH):$(FATFS_DIR)
+endif
+
+ifneq ($(filter SDCARD_SDIO,$(FEATURES)),)
INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(FATFS_DIR)
VPATH := $(VPATH):$(FATFS_DIR)
@@ -202,12 +208,12 @@ MSC_SRC = \
msc/usbd_msc_desc.c \
msc/usbd_storage.c
-ifneq ($(filter SDCARD,$(FEATURES)),)
+ifneq ($(filter SDCARD_SPI,$(FEATURES)),)
MSC_SRC += \
msc/usbd_storage_sd_spi.c
endif
-ifneq ($(filter SDIO,$(FEATURES)),)
+ifneq ($(filter SDCARD_SDIO,$(FEATURES)),)
MSC_SRC += \
msc/usbd_storage_sdio.c
MCU_COMMON_SRC += \
diff --git a/make/mcu/STM32F7.mk b/make/mcu/STM32F7.mk
index 0cb1eb3fde..2c5733415c 100644
--- a/make/mcu/STM32F7.mk
+++ b/make/mcu/STM32F7.mk
@@ -117,7 +117,13 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(ROOT)/lib/main/STM32F7/Drivers/CMSIS/Device/ST/STM32F7xx/Include \
$(ROOT)/src/main/vcp_hal
-ifneq ($(filter SDCARD,$(FEATURES)),)
+ifneq ($(filter SDCARD_SPI,$(FEATURES)),)
+INCLUDE_DIRS := $(INCLUDE_DIRS) \
+ $(FATFS_DIR)
+VPATH := $(VPATH):$(FATFS_DIR)
+endif
+
+ifneq ($(filter SDCARD_SDIO,$(FEATURES)),)
INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(FATFS_DIR)
VPATH := $(VPATH):$(FATFS_DIR)
@@ -189,14 +195,14 @@ MSC_SRC = \
drivers/usb_msc_f7xx.c \
msc/usbd_storage.c
-ifneq ($(filter SDIO,$(FEATURES)),)
+ifneq ($(filter SDCARD_SDIO,$(FEATURES)),)
MCU_COMMON_SRC += \
drivers/sdio_f7xx.c
MSC_SRC += \
msc/usbd_storage_sdio.c
endif
-ifneq ($(filter SDCARD,$(FEATURES)),)
+ifneq ($(filter SDCARD_SPI,$(FEATURES)),)
MSC_SRC += \
msc/usbd_storage_sd_spi.c
endif
diff --git a/make/source.mk b/make/source.mk
index 38fbc76dcd..c17feaaabf 100644
--- a/make/source.mk
+++ b/make/source.mk
@@ -355,17 +355,19 @@ SRC += $(COMMON_SRC)
#excludes
SRC := $(filter-out $(MCU_EXCLUDES), $(SRC))
-ifneq ($(filter SDCARD,$(FEATURES)),)
+ifneq ($(filter SDCARD_SPI,$(FEATURES)),)
SRC += \
drivers/sdcard.c \
+ drivers/sdcard_spi.c \
drivers/sdcard_standard.c \
io/asyncfatfs/asyncfatfs.c \
io/asyncfatfs/fat_standard.c \
$(MSC_SRC)
endif
-ifneq ($(filter SDIO,$(FEATURES)),)
+ifneq ($(filter SDCARD_SDIO,$(FEATURES)),)
SRC += \
+ drivers/sdcard.c \
drivers/sdcard_sdio_baremetal.c \
drivers/sdcard_standard.c \
io/asyncfatfs/asyncfatfs.c \
diff --git a/src/main/drivers/sdcard.c b/src/main/drivers/sdcard.c
index d296d97edc..45f2b27f2b 100644
--- a/src/main/drivers/sdcard.c
+++ b/src/main/drivers/sdcard.c
@@ -33,6 +33,7 @@
#include "drivers/time.h"
#include "sdcard.h"
+#include "sdcard_impl.h"
#include "sdcard_standard.h"
#ifdef AFATFS_USE_INTROSPECTIVE_LOGGING
@@ -58,64 +59,7 @@
*/
#define SDCARD_NON_DMA_CHUNK_SIZE 256
-typedef enum {
- // In these states we run at the initialization 400kHz clockspeed:
- SDCARD_STATE_NOT_PRESENT = 0,
- SDCARD_STATE_RESET,
- SDCARD_STATE_CARD_INIT_IN_PROGRESS,
- SDCARD_STATE_INITIALIZATION_RECEIVE_CID,
-
- // In these states we run at full clock speed
- SDCARD_STATE_READY,
- SDCARD_STATE_READING,
- SDCARD_STATE_SENDING_WRITE,
- SDCARD_STATE_WAITING_FOR_WRITE,
- SDCARD_STATE_WRITING_MULTIPLE_BLOCKS,
- SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE
-} sdcardState_e;
-
-typedef struct sdcard_t {
- struct {
- uint8_t *buffer;
- uint32_t blockIndex;
- uint8_t chunkIndex;
-
- sdcard_operationCompleteCallback_c callback;
- uint32_t callbackData;
-
-#ifdef SDCARD_PROFILING
- uint32_t profileStartTime;
-#endif
- } pendingOperation;
-
- uint32_t operationStartTime;
-
- uint8_t failureCount;
-
- uint8_t version;
- bool highCapacity;
-
- uint32_t multiWriteNextBlock;
- uint32_t multiWriteBlocksRemain;
-
- sdcardState_e state;
-
- sdcardMetadata_t metadata;
- sdcardCSD_t csd;
-
-#ifdef SDCARD_PROFILING
- sdcard_profilerCallback_c profiler;
-#endif
- busDevice_t busdev;
- bool enabled;
- bool detectionInverted;
- bool useDMAForTx;
- IO_t cardDetectPin;
- dmaChannelDescriptor_t * dma;
- uint8_t dmaChannel;
-} sdcard_t;
-
-static sdcard_t sdcard;
+sdcard_t sdcard;
STATIC_ASSERT(sizeof(sdcardCSD_t) == 16, sdcard_csd_bitfields_didnt_pack_properly);
@@ -149,1023 +93,4 @@ bool sdcard_isInserted(void)
}
return result;
}
-
-/**
- * Returns true if the card has already been, or is currently, initializing and hasn't encountered enough errors to
- * trip our error threshold and be disabled (i.e. our card is in and working!)
- */
-bool sdcard_isFunctional(void)
-{
- return sdcard.state != SDCARD_STATE_NOT_PRESENT;
-}
-
-static void sdcard_select(void)
-{
- IOLo(sdcard.busdev.busdev_u.spi.csnPin);
-}
-
-static void sdcard_deselect(void)
-{
- // As per the SD-card spec, give the card 8 dummy clocks so it can finish its operation
- //spiTransferByte(sdcard.busdev.busdev_u.spi.instance, 0xFF);
-
- while (spiIsBusBusy(sdcard.busdev.busdev_u.spi.instance)) {
- }
-
- IOHi(sdcard.busdev.busdev_u.spi.csnPin);
-}
-
-/**
- * Handle a failure of an SD card operation by resetting the card back to its initialization phase.
- *
- * Increments the failure counter, and when the failure threshold is reached, disables the card until
- * the next call to sdcard_init().
- */
-static void sdcard_reset(void)
-{
- if (!sdcard_isInserted()) {
- sdcard.state = SDCARD_STATE_NOT_PRESENT;
- return;
- }
-
- if (sdcard.state >= SDCARD_STATE_READY) {
- spiSetDivisor(sdcard.busdev.busdev_u.spi.instance, SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER);
- }
-
- sdcard.failureCount++;
- if (sdcard.failureCount >= SDCARD_MAX_CONSECUTIVE_FAILURES) {
- sdcard.state = SDCARD_STATE_NOT_PRESENT;
- } else {
- sdcard.operationStartTime = millis();
- sdcard.state = SDCARD_STATE_RESET;
- }
-}
-
-/**
- * The SD card spec requires 8 clock cycles to be sent by us on the bus after most commands so it can finish its
- * processing of that command. The easiest way for us to do this is to just wait for the bus to become idle before
- * we transmit a command, sending at least 8-bits onto the bus when we do so.
- */
-static bool sdcard_waitForIdle(int maxBytesToWait)
-{
- while (maxBytesToWait > 0) {
- uint8_t b = spiTransferByte(sdcard.busdev.busdev_u.spi.instance, 0xFF);
- if (b == 0xFF) {
- return true;
- }
- maxBytesToWait--;
- }
-
- return false;
-}
-
-/**
- * Wait for up to maxDelay 0xFF idle bytes to arrive from the card, returning the first non-idle byte found.
- *
- * Returns 0xFF on failure.
- */
-static uint8_t sdcard_waitForNonIdleByte(int maxDelay)
-{
- for (int i = 0; i < maxDelay + 1; i++) { // + 1 so we can wait for maxDelay '0xFF' bytes before reading a response byte afterwards
- uint8_t response = spiTransferByte(sdcard.busdev.busdev_u.spi.instance, 0xFF);
-
- if (response != 0xFF) {
- return response;
- }
- }
-
- return 0xFF;
-}
-
-/**
- * Waits up to SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY bytes for the card to become ready, send a command to the card
- * with the given argument, waits up to SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY bytes for a reply, and returns the
- * first non-0xFF byte of the reply.
- *
- * You must select the card first with sdcard_select() and deselect it afterwards with sdcard_deselect().
- *
- * Upon failure, 0xFF is returned.
- */
-static uint8_t sdcard_sendCommand(uint8_t commandCode, uint32_t commandArgument)
-{
- const uint8_t command[6] = {
- 0x40 | commandCode,
- commandArgument >> 24,
- commandArgument >> 16,
- commandArgument >> 8,
- commandArgument,
- 0x95 /* Static CRC. This CRC is valid for CMD0 with a 0 argument, and CMD8 with 0x1AB argument, which are the only
- commands that require a CRC */
- };
-
- // Go ahead and send the command even if the card isn't idle if this is the reset command
- if (!sdcard_waitForIdle(SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY) && commandCode != SDCARD_COMMAND_GO_IDLE_STATE)
- return 0xFF;
-
- spiTransfer(sdcard.busdev.busdev_u.spi.instance, command, NULL, sizeof(command));
-
- /*
- * The card can take up to SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY bytes to send the response, in the meantime
- * it'll transmit 0xFF filler bytes.
- */
- return sdcard_waitForNonIdleByte(SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY);
-}
-
-static uint8_t sdcard_sendAppCommand(uint8_t commandCode, uint32_t commandArgument)
-{
- sdcard_sendCommand(SDCARD_COMMAND_APP_CMD, 0);
-
- return sdcard_sendCommand(commandCode, commandArgument);
-}
-
-/**
- * Sends an IF_COND message to the card to check its version and validate its voltage requirements. Sets the global
- * sdCardVersion with the detected version (0, 1, or 2) and returns true if the card is compatible.
- */
-static bool sdcard_validateInterfaceCondition(void)
-{
- uint8_t ifCondReply[4];
-
- sdcard.version = 0;
-
- sdcard_select();
-
- uint8_t status = sdcard_sendCommand(SDCARD_COMMAND_SEND_IF_COND, (SDCARD_VOLTAGE_ACCEPTED_2_7_to_3_6 << 8) | SDCARD_IF_COND_CHECK_PATTERN);
-
- // Don't deselect the card right away, because we'll want to read the rest of its reply if it's a V2 card
-
- if (status == (SDCARD_R1_STATUS_BIT_ILLEGAL_COMMAND | SDCARD_R1_STATUS_BIT_IDLE)) {
- // V1 cards don't support this command
- sdcard.version = 1;
- } else if (status == SDCARD_R1_STATUS_BIT_IDLE) {
- spiTransfer(sdcard.busdev.busdev_u.spi.instance, NULL, ifCondReply, sizeof(ifCondReply));
-
- /*
- * We don't bother to validate the SDCard's operating voltage range since the spec requires it to accept our
- * 3.3V, but do check that it echoed back our check pattern properly.
- */
- if (ifCondReply[3] == SDCARD_IF_COND_CHECK_PATTERN) {
- sdcard.version = 2;
- }
- }
-
- sdcard_deselect();
-
- return sdcard.version > 0;
-}
-
-static bool sdcard_readOCRRegister(uint32_t *result)
-{
- sdcard_select();
-
- uint8_t status = sdcard_sendCommand(SDCARD_COMMAND_READ_OCR, 0);
-
- uint8_t response[4];
-
- spiTransfer(sdcard.busdev.busdev_u.spi.instance, NULL, response, sizeof(response));
-
- if (status == 0) {
- sdcard_deselect();
-
- *result = (response[0] << 24) | (response[1] << 16) | (response[2] << 8) | response[3];
-
- return true;
- } else {
- sdcard_deselect();
-
- return false;
- }
-}
-
-typedef enum {
- SDCARD_RECEIVE_SUCCESS,
- SDCARD_RECEIVE_BLOCK_IN_PROGRESS,
- SDCARD_RECEIVE_ERROR
-} sdcardReceiveBlockStatus_e;
-
-/**
- * Attempt to receive a data block from the SD card.
- *
- * Return true on success, otherwise the card has not responded yet and you should retry later.
- */
-static sdcardReceiveBlockStatus_e sdcard_receiveDataBlock(uint8_t *buffer, int count)
-{
- uint8_t dataToken = sdcard_waitForNonIdleByte(8);
-
- if (dataToken == 0xFF) {
- return SDCARD_RECEIVE_BLOCK_IN_PROGRESS;
- }
-
- if (dataToken != SDCARD_SINGLE_BLOCK_READ_START_TOKEN) {
- return SDCARD_RECEIVE_ERROR;
- }
-
- spiTransfer(sdcard.busdev.busdev_u.spi.instance, NULL, buffer, count);
-
- // Discard trailing CRC, we don't care
- spiTransferByte(sdcard.busdev.busdev_u.spi.instance, 0xFF);
- spiTransferByte(sdcard.busdev.busdev_u.spi.instance, 0xFF);
-
- return SDCARD_RECEIVE_SUCCESS;
-}
-
-static bool sdcard_sendDataBlockFinish(void)
-{
-#ifdef USE_HAL_DRIVER
- // Drain anything left in the Rx FIFO (we didn't read it during the write)
- //This is necessary here as when using msc there is timing issue
- while (LL_SPI_IsActiveFlag_RXNE(sdcard.busdev.busdev_u.spi.instance)) {
- sdcard.busdev.busdev_u.spi.instance->DR;
- }
-#endif
-
- // Send a dummy CRC
- spiTransferByte(sdcard.busdev.busdev_u.spi.instance, 0x00);
- spiTransferByte(sdcard.busdev.busdev_u.spi.instance, 0x00);
-
- uint8_t dataResponseToken = spiTransferByte(sdcard.busdev.busdev_u.spi.instance, 0xFF);
-
- /*
- * Check if the card accepted the write (no CRC error / no address error)
- *
- * The lower 5 bits are structured as follows:
- * | 0 | Status | 1 |
- * | 0 | x x x | 1 |
- *
- * Statuses:
- * 010 - Data accepted
- * 101 - CRC error
- * 110 - Write error
- */
- return (dataResponseToken & 0x1F) == 0x05;
-}
-
-/**
- * Begin sending a buffer of SDCARD_BLOCK_SIZE bytes to the SD card.
- */
-static void sdcard_sendDataBlockBegin(const uint8_t *buffer, bool multiBlockWrite)
-{
- // Card wants 8 dummy clock cycles between the write command's response and a data block beginning:
- spiTransferByte(sdcard.busdev.busdev_u.spi.instance, 0xFF);
-
- spiTransferByte(sdcard.busdev.busdev_u.spi.instance, multiBlockWrite ? SDCARD_MULTIPLE_BLOCK_WRITE_START_TOKEN : SDCARD_SINGLE_BLOCK_WRITE_START_TOKEN);
-
- if (sdcard.useDMAForTx) {
-#if defined(USE_HAL_DRIVER)
- LL_DMA_InitTypeDef init;
-
- LL_DMA_StructInit(&init);
-
- init.Channel = dmaGetChannel(sdcard.dmaChannel);
- init.Mode = LL_DMA_MODE_NORMAL;
- init.Direction = LL_DMA_DIRECTION_MEMORY_TO_PERIPH;
-
- init.PeriphOrM2MSrcAddress = (uint32_t)&sdcard.busdev.busdev_u.spi.instance->DR;
- init.Priority = LL_DMA_PRIORITY_LOW;
- init.PeriphOrM2MSrcIncMode = LL_DMA_PERIPH_NOINCREMENT;
- init.PeriphOrM2MSrcDataSize = LL_DMA_PDATAALIGN_BYTE;
-
- init.MemoryOrM2MDstAddress = (uint32_t)buffer;
- init.MemoryOrM2MDstIncMode = LL_DMA_MEMORY_INCREMENT;
- init.MemoryOrM2MDstDataSize = LL_DMA_MDATAALIGN_BYTE;
-
- init.NbData = SDCARD_BLOCK_SIZE;
-
- LL_DMA_DeInit(sdcard.dma->dma, sdcard.dma->stream);
- LL_DMA_Init(sdcard.dma->dma, sdcard.dma->stream, &init);
-
- LL_DMA_EnableStream(sdcard.dma->dma, sdcard.dma->stream);
-
- LL_SPI_EnableDMAReq_TX(sdcard.busdev.busdev_u.spi.instance);
-
-#else
-
- DMA_InitTypeDef init;
-
- DMA_StructInit(&init);
-#ifdef STM32F4
- init.DMA_Channel = dmaGetChannel(sdcard.dmaChannel);
- init.DMA_Memory0BaseAddr = (uint32_t) buffer;
- init.DMA_DIR = DMA_DIR_MemoryToPeripheral;
-#else
- init.DMA_M2M = DMA_M2M_Disable;
- init.DMA_MemoryBaseAddr = (uint32_t) buffer;
- init.DMA_DIR = DMA_DIR_PeripheralDST;
-#endif
- init.DMA_PeripheralBaseAddr = (uint32_t) &sdcard.busdev.busdev_u.spi.instance->DR;
- init.DMA_Priority = DMA_Priority_Low;
- init.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
- init.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
-
- init.DMA_MemoryInc = DMA_MemoryInc_Enable;
- init.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
-
- init.DMA_BufferSize = SDCARD_BLOCK_SIZE;
- init.DMA_Mode = DMA_Mode_Normal;
-
- DMA_DeInit(sdcard.dma->ref);
- DMA_Init(sdcard.dma->ref, &init);
-
- DMA_Cmd(sdcard.dma->ref, ENABLE);
-
- SPI_I2S_DMACmd(sdcard.busdev.busdev_u.spi.instance, SPI_I2S_DMAReq_Tx, ENABLE);
-#endif
- } else {
- // Send the first chunk now
- spiTransfer(sdcard.busdev.busdev_u.spi.instance, buffer, NULL, SDCARD_NON_DMA_CHUNK_SIZE);
- }
-}
-
-static bool sdcard_receiveCID(void)
-{
- uint8_t cid[16];
-
- if (sdcard_receiveDataBlock(cid, sizeof(cid)) != SDCARD_RECEIVE_SUCCESS) {
- return false;
- }
-
- sdcard.metadata.manufacturerID = cid[0];
- sdcard.metadata.oemID = (cid[1] << 8) | cid[2];
- sdcard.metadata.productName[0] = cid[3];
- sdcard.metadata.productName[1] = cid[4];
- sdcard.metadata.productName[2] = cid[5];
- sdcard.metadata.productName[3] = cid[6];
- sdcard.metadata.productName[4] = cid[7];
- sdcard.metadata.productRevisionMajor = cid[8] >> 4;
- sdcard.metadata.productRevisionMinor = cid[8] & 0x0F;
- sdcard.metadata.productSerial = (cid[9] << 24) | (cid[10] << 16) | (cid[11] << 8) | cid[12];
- sdcard.metadata.productionYear = (((cid[13] & 0x0F) << 4) | (cid[14] >> 4)) + 2000;
- sdcard.metadata.productionMonth = cid[14] & 0x0F;
-
- return true;
-}
-
-static bool sdcard_fetchCSD(void)
-{
- uint32_t readBlockLen, blockCount, blockCountMult;
- uint64_t capacityBytes;
-
- sdcard_select();
-
- /* The CSD command's data block should always arrive within 8 idle clock cycles (SD card spec). This is because
- * the information about card latency is stored in the CSD register itself, so we can't use that yet!
- */
- bool success =
- sdcard_sendCommand(SDCARD_COMMAND_SEND_CSD, 0) == 0
- && sdcard_receiveDataBlock((uint8_t*) &sdcard.csd, sizeof(sdcard.csd)) == SDCARD_RECEIVE_SUCCESS
- && SDCARD_GET_CSD_FIELD(sdcard.csd, 1, TRAILER) == 1;
-
- if (success) {
- switch (SDCARD_GET_CSD_FIELD(sdcard.csd, 1, CSD_STRUCTURE_VER)) {
- case SDCARD_CSD_STRUCTURE_VERSION_1:
- // Block size in bytes (doesn't have to be 512)
- readBlockLen = 1 << SDCARD_GET_CSD_FIELD(sdcard.csd, 1, READ_BLOCK_LEN);
- blockCountMult = 1 << (SDCARD_GET_CSD_FIELD(sdcard.csd, 1, CSIZE_MULT) + 2);
- blockCount = (SDCARD_GET_CSD_FIELD(sdcard.csd, 1, CSIZE) + 1) * blockCountMult;
-
- // We could do this in 32 bits but it makes the 2GB case awkward
- capacityBytes = (uint64_t) blockCount * readBlockLen;
-
- // Re-express that capacity (max 2GB) in our standard 512-byte block size
- sdcard.metadata.numBlocks = capacityBytes / SDCARD_BLOCK_SIZE;
- break;
- case SDCARD_CSD_STRUCTURE_VERSION_2:
- sdcard.metadata.numBlocks = (SDCARD_GET_CSD_FIELD(sdcard.csd, 2, CSIZE) + 1) * 1024;
- break;
- default:
- success = false;
- }
- }
-
- sdcard_deselect();
-
- return success;
-}
-
-/**
- * Check if the SD Card has completed its startup sequence. Must be called with sdcard.state == SDCARD_STATE_INITIALIZATION.
- *
- * Returns true if the card has finished its init process.
- */
-static bool sdcard_checkInitDone(void)
-{
- sdcard_select();
-
- uint8_t status = sdcard_sendAppCommand(SDCARD_ACOMMAND_SEND_OP_COND, sdcard.version == 2 ? 1 << 30 /* We support high capacity cards */ : 0);
-
- sdcard_deselect();
-
- // When card init is complete, the idle bit in the response becomes zero.
- return status == 0x00;
-}
-
-/**
- * Begin the initialization process for the SD card. This must be called first before any other sdcard_ routine.
- */
-void sdcard_init(const sdcardConfig_t *config)
-{
- sdcard.enabled = config->enabled;
- if (!sdcard.enabled) {
- sdcard.state = SDCARD_STATE_NOT_PRESENT;
- return;
- }
-
- spiBusSetInstance(&sdcard.busdev, spiInstanceByDevice(config->device));
-
- sdcard.useDMAForTx = config->useDma;
- if (sdcard.useDMAForTx) {
-#if defined(STM32F4) || defined(STM32F7)
- sdcard.dmaChannel = config->dmaChannel;
-#endif
- sdcard.dma = dmaGetDescriptorByIdentifier(config->dmaIdentifier);
- dmaInit(config->dmaIdentifier, OWNER_SDCARD, 0);
- }
-
- IO_t chipSelectIO;
- if (config->chipSelectTag) {
- chipSelectIO = IOGetByTag(config->chipSelectTag);
- IOInit(chipSelectIO, OWNER_SDCARD_CS, 0);
- IOConfigGPIO(chipSelectIO, SPI_IO_CS_CFG);
- } else {
- chipSelectIO = IO_NONE;
- }
- sdcard.busdev.busdev_u.spi.csnPin = chipSelectIO;
-
- if (config->cardDetectTag) {
- sdcard.cardDetectPin = IOGetByTag(config->cardDetectTag);
- sdcard.detectionInverted = config->cardDetectInverted;
- } else {
- sdcard.cardDetectPin = IO_NONE;
- sdcard.detectionInverted = false;
- }
-
- // Max frequency is initially 400kHz
- spiSetDivisor(sdcard.busdev.busdev_u.spi.instance, SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER);
-
- // SDCard wants 1ms minimum delay after power is applied to it
- delay(1000);
-
- // Transmit at least 74 dummy clock cycles with CS high so the SD card can start up
- IOHi(sdcard.busdev.busdev_u.spi.csnPin);
-
- spiTransfer(sdcard.busdev.busdev_u.spi.instance, NULL, NULL, SDCARD_INIT_NUM_DUMMY_BYTES);
-
- // Wait for that transmission to finish before we enable the SDCard, so it receives the required number of cycles:
- int time = 100000;
- while (spiIsBusBusy(sdcard.busdev.busdev_u.spi.instance)) {
- if (time-- == 0) {
- sdcard.state = SDCARD_STATE_NOT_PRESENT;
- sdcard.failureCount++;
- return;
- }
- }
-
- sdcard.operationStartTime = millis();
- sdcard.state = SDCARD_STATE_RESET;
- sdcard.failureCount = 0;
-}
-
-static bool sdcard_setBlockLength(uint32_t blockLen)
-{
- sdcard_select();
-
- uint8_t status = sdcard_sendCommand(SDCARD_COMMAND_SET_BLOCKLEN, blockLen);
-
- sdcard_deselect();
-
- return status == 0;
-}
-
-/*
- * Returns true if the card is ready to accept read/write commands.
- */
-static bool sdcard_isReady(void)
-{
- return sdcard.state == SDCARD_STATE_READY || sdcard.state == SDCARD_STATE_WRITING_MULTIPLE_BLOCKS;
-}
-
-/**
- * Send the stop-transmission token to complete a multi-block write.
- *
- * Returns:
- * SDCARD_OPERATION_IN_PROGRESS - We're now waiting for that stop to complete, the card will enter
- * the SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE state.
- * SDCARD_OPERATION_SUCCESS - The multi-block write finished immediately, the card will enter
- * the SDCARD_READY state.
- *
- */
-static sdcardOperationStatus_e sdcard_endWriteBlocks(void)
-{
- sdcard.multiWriteBlocksRemain = 0;
-
- // 8 dummy clocks to guarantee N_WR clocks between the last card response and this token
- spiTransferByte(sdcard.busdev.busdev_u.spi.instance, 0xFF);
-
- spiTransferByte(sdcard.busdev.busdev_u.spi.instance, SDCARD_MULTIPLE_BLOCK_WRITE_STOP_TOKEN);
-
- // Card may choose to raise a busy (non-0xFF) signal after at most N_BR (1 byte) delay
- if (sdcard_waitForNonIdleByte(1) == 0xFF) {
- sdcard.state = SDCARD_STATE_READY;
- return SDCARD_OPERATION_SUCCESS;
- } else {
- sdcard.state = SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE;
- sdcard.operationStartTime = millis();
-
- return SDCARD_OPERATION_IN_PROGRESS;
- }
-}
-
-/**
- * Call periodically for the SD card to perform in-progress transfers.
- *
- * Returns true if the card is ready to accept commands.
- */
-bool sdcard_poll(void)
-{
- if (!sdcard.enabled) {
- sdcard.state = SDCARD_STATE_NOT_PRESENT;
- return false;
- }
-
- uint8_t initStatus;
- bool sendComplete;
-
-#ifdef SDCARD_PROFILING
- bool profilingComplete;
-#endif
-
- doMore:
- switch (sdcard.state) {
- case SDCARD_STATE_RESET:
- sdcard_select();
-
- initStatus = sdcard_sendCommand(SDCARD_COMMAND_GO_IDLE_STATE, 0);
-
- sdcard_deselect();
-
- if (initStatus == SDCARD_R1_STATUS_BIT_IDLE) {
- // Check card voltage and version
- if (sdcard_validateInterfaceCondition()) {
-
- sdcard.state = SDCARD_STATE_CARD_INIT_IN_PROGRESS;
- goto doMore;
- } else {
- // Bad reply/voltage, we ought to refrain from accessing the card.
- sdcard.state = SDCARD_STATE_NOT_PRESENT;
- }
- }
- break;
-
- case SDCARD_STATE_CARD_INIT_IN_PROGRESS:
- if (sdcard_checkInitDone()) {
- if (sdcard.version == 2) {
- // Check for high capacity card
- uint32_t ocr;
-
- if (!sdcard_readOCRRegister(&ocr)) {
- sdcard_reset();
- goto doMore;
- }
-
- sdcard.highCapacity = (ocr & (1 << 30)) != 0;
- } else {
- // Version 1 cards are always low-capacity
- sdcard.highCapacity = false;
- }
-
- // Now fetch the CSD and CID registers
- if (sdcard_fetchCSD()) {
- sdcard_select();
-
- uint8_t status = sdcard_sendCommand(SDCARD_COMMAND_SEND_CID, 0);
-
- if (status == 0) {
- // Keep the card selected to receive the response block
- sdcard.state = SDCARD_STATE_INITIALIZATION_RECEIVE_CID;
- goto doMore;
- } else {
- sdcard_deselect();
-
- sdcard_reset();
- goto doMore;
- }
- }
- }
- break;
- case SDCARD_STATE_INITIALIZATION_RECEIVE_CID:
- if (sdcard_receiveCID()) {
- sdcard_deselect();
-
- /* The spec is a little iffy on what the default block size is for Standard Size cards (it can be changed on
- * standard size cards) so let's just set it to 512 explicitly so we don't have a problem.
- */
- if (!sdcard.highCapacity && !sdcard_setBlockLength(SDCARD_BLOCK_SIZE)) {
- sdcard_reset();
- goto doMore;
- }
-
- // Now we're done with init and we can switch to the full speed clock (<25MHz)
- spiSetDivisor(sdcard.busdev.busdev_u.spi.instance, SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER);
-
- sdcard.multiWriteBlocksRemain = 0;
-
- sdcard.state = SDCARD_STATE_READY;
- goto doMore;
- } // else keep waiting for the CID to arrive
- break;
- case SDCARD_STATE_SENDING_WRITE:
- // Have we finished sending the write yet?
- sendComplete = false;
-
-#if defined(USE_HAL_DRIVER)
- if (sdcard.useDMAForTx && DMA_GET_FLAG_STATUS(sdcard.dma, DMA_IT_TCIF)) {
- //Clear both flags after transfer
- DMA_CLEAR_FLAG(sdcard.dma, DMA_IT_TCIF);
- DMA_CLEAR_FLAG(sdcard.dma, DMA_IT_HTIF);
- // Drain anything left in the Rx FIFO (we didn't read it during the write)
- while (LL_SPI_IsActiveFlag_RXNE(sdcard.busdev.busdev_u.spi.instance)) {
- sdcard.busdev.busdev_u.spi.instance->DR;
- }
-
- // Wait for the final bit to be transmitted
- while (spiIsBusBusy(sdcard.busdev.busdev_u.spi.instance)) {
- }
-
- LL_SPI_DisableDMAReq_TX(sdcard.busdev.busdev_u.spi.instance);
-
- sendComplete = true;
- }
-#else
-#ifdef STM32F4
- if (sdcard.useDMAForTx && DMA_GetFlagStatus(sdcard.dma->ref, sdcard.dma->completeFlag) == SET) {
- DMA_ClearFlag(sdcard.dma->ref, sdcard.dma->completeFlag);
-#else
- if (sdcard.useDMAForTx && DMA_GetFlagStatus(sdcard.dma->completeFlag) == SET) {
- DMA_ClearFlag(sdcard.dma->completeFlag);
-#endif
-
- DMA_Cmd(sdcard.dma->ref, DISABLE);
-
- // Drain anything left in the Rx FIFO (we didn't read it during the write)
- while (SPI_I2S_GetFlagStatus(sdcard.busdev.busdev_u.spi.instance, SPI_I2S_FLAG_RXNE) == SET) {
- sdcard.busdev.busdev_u.spi.instance->DR;
- }
-
- // Wait for the final bit to be transmitted
- while (spiIsBusBusy(sdcard.busdev.busdev_u.spi.instance)) {
- }
-
- SPI_I2S_DMACmd(sdcard.busdev.busdev_u.spi.instance, SPI_I2S_DMAReq_Tx, DISABLE);
-
- sendComplete = true;
- }
-#endif
- if (!sdcard.useDMAForTx) {
- // Send another chunk
- spiTransfer(sdcard.busdev.busdev_u.spi.instance, sdcard.pendingOperation.buffer + SDCARD_NON_DMA_CHUNK_SIZE * sdcard.pendingOperation.chunkIndex, NULL, SDCARD_NON_DMA_CHUNK_SIZE);
-
- sdcard.pendingOperation.chunkIndex++;
-
- sendComplete = sdcard.pendingOperation.chunkIndex == SDCARD_BLOCK_SIZE / SDCARD_NON_DMA_CHUNK_SIZE;
- }
-
- if (sendComplete) {
- // Finish up by sending the CRC and checking the SD-card's acceptance/rejectance
- if (sdcard_sendDataBlockFinish()) {
- // The SD card is now busy committing that write to the card
- sdcard.state = SDCARD_STATE_WAITING_FOR_WRITE;
- sdcard.operationStartTime = millis();
-
- // Since we've transmitted the buffer we can go ahead and tell the caller their operation is complete
- if (sdcard.pendingOperation.callback) {
- sdcard.pendingOperation.callback(SDCARD_BLOCK_OPERATION_WRITE, sdcard.pendingOperation.blockIndex, sdcard.pendingOperation.buffer, sdcard.pendingOperation.callbackData);
- }
- } else {
- /* Our write was rejected! This could be due to a bad address but we hope not to attempt that, so assume
- * the card is broken and needs reset.
- */
- sdcard_reset();
-
- // Announce write failure:
- if (sdcard.pendingOperation.callback) {
- sdcard.pendingOperation.callback(SDCARD_BLOCK_OPERATION_WRITE, sdcard.pendingOperation.blockIndex, NULL, sdcard.pendingOperation.callbackData);
- }
-
- goto doMore;
- }
- }
- break;
- case SDCARD_STATE_WAITING_FOR_WRITE:
- if (sdcard_waitForIdle(SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY)) {
-#ifdef SDCARD_PROFILING
- profilingComplete = true;
-#endif
-
- sdcard.failureCount = 0; // Assume the card is good if it can complete a write
-
- // Still more blocks left to write in a multi-block chain?
- if (sdcard.multiWriteBlocksRemain > 1) {
- sdcard.multiWriteBlocksRemain--;
- sdcard.multiWriteNextBlock++;
- sdcard.state = SDCARD_STATE_WRITING_MULTIPLE_BLOCKS;
- } else if (sdcard.multiWriteBlocksRemain == 1) {
- // This function changes the sd card state for us whether immediately succesful or delayed:
- if (sdcard_endWriteBlocks() == SDCARD_OPERATION_SUCCESS) {
- sdcard_deselect();
- } else {
-#ifdef SDCARD_PROFILING
- // Wait for the multi-block write to be terminated before finishing timing
- profilingComplete = false;
-#endif
- }
- } else {
- sdcard.state = SDCARD_STATE_READY;
- sdcard_deselect();
- }
-
-#ifdef SDCARD_PROFILING
- if (profilingComplete && sdcard.profiler) {
- sdcard.profiler(SDCARD_BLOCK_OPERATION_WRITE, sdcard.pendingOperation.blockIndex, micros() - sdcard.pendingOperation.profileStartTime);
- }
-#endif
- } else if (millis() > sdcard.operationStartTime + SDCARD_TIMEOUT_WRITE_MSEC) {
- /*
- * The caller has already been told that their write has completed, so they will have discarded
- * their buffer and have no hope of retrying the operation. But this should be very rare and it allows
- * them to reuse their buffer milliseconds faster than they otherwise would.
- */
- sdcard_reset();
- goto doMore;
- }
- break;
- case SDCARD_STATE_READING:
- switch (sdcard_receiveDataBlock(sdcard.pendingOperation.buffer, SDCARD_BLOCK_SIZE)) {
- case SDCARD_RECEIVE_SUCCESS:
- sdcard_deselect();
-
- sdcard.state = SDCARD_STATE_READY;
- sdcard.failureCount = 0; // Assume the card is good if it can complete a read
-
-#ifdef SDCARD_PROFILING
- if (sdcard.profiler) {
- sdcard.profiler(SDCARD_BLOCK_OPERATION_READ, sdcard.pendingOperation.blockIndex, micros() - sdcard.pendingOperation.profileStartTime);
- }
-#endif
-
- if (sdcard.pendingOperation.callback) {
- sdcard.pendingOperation.callback(
- SDCARD_BLOCK_OPERATION_READ,
- sdcard.pendingOperation.blockIndex,
- sdcard.pendingOperation.buffer,
- sdcard.pendingOperation.callbackData
- );
- }
- break;
- case SDCARD_RECEIVE_BLOCK_IN_PROGRESS:
- if (millis() <= sdcard.operationStartTime + SDCARD_TIMEOUT_READ_MSEC) {
- break; // Timeout not reached yet so keep waiting
- }
- // Timeout has expired, so fall through to convert to a fatal error
- FALLTHROUGH;
-
- case SDCARD_RECEIVE_ERROR:
- sdcard_deselect();
-
- sdcard_reset();
-
- if (sdcard.pendingOperation.callback) {
- sdcard.pendingOperation.callback(
- SDCARD_BLOCK_OPERATION_READ,
- sdcard.pendingOperation.blockIndex,
- NULL,
- sdcard.pendingOperation.callbackData
- );
- }
-
- goto doMore;
- break;
- }
- break;
- case SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE:
- if (sdcard_waitForIdle(SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY)) {
- sdcard_deselect();
-
- sdcard.state = SDCARD_STATE_READY;
-
-#ifdef SDCARD_PROFILING
- if (sdcard.profiler) {
- sdcard.profiler(SDCARD_BLOCK_OPERATION_WRITE, sdcard.pendingOperation.blockIndex, micros() - sdcard.pendingOperation.profileStartTime);
- }
-#endif
- } else if (millis() > sdcard.operationStartTime + SDCARD_TIMEOUT_WRITE_MSEC) {
- sdcard_reset();
- goto doMore;
- }
- break;
- case SDCARD_STATE_NOT_PRESENT:
- default:
- ;
- }
-
- // Is the card's initialization taking too long?
- if (sdcard.state >= SDCARD_STATE_RESET && sdcard.state < SDCARD_STATE_READY
- && millis() - sdcard.operationStartTime > SDCARD_TIMEOUT_INIT_MILLIS) {
- sdcard_reset();
- }
-
- return sdcard_isReady();
-}
-
-/**
- * Write the 512-byte block from the given buffer into the block with the given index.
- *
- * If the write does not complete immediately, your callback will be called later. If the write was successful, the
- * buffer pointer will be the same buffer you originally passed in, otherwise the buffer will be set to NULL.
- *
- * Returns:
- * SDCARD_OPERATION_IN_PROGRESS - Your buffer is currently being transmitted to the card and your callback will be
- * called later to report the completion. The buffer pointer must remain valid until
- * that time.
- * SDCARD_OPERATION_SUCCESS - Your buffer has been transmitted to the card now.
- * SDCARD_OPERATION_BUSY - The card is already busy and cannot accept your write
- * SDCARD_OPERATION_FAILURE - Your write was rejected by the card, card will be reset
- */
-sdcardOperationStatus_e sdcard_writeBlock(uint32_t blockIndex, uint8_t *buffer, sdcard_operationCompleteCallback_c callback, uint32_t callbackData)
-{
- uint8_t status;
-
-#ifdef SDCARD_PROFILING
- sdcard.pendingOperation.profileStartTime = micros();
-#endif
-
- doMore:
- switch (sdcard.state) {
- case SDCARD_STATE_WRITING_MULTIPLE_BLOCKS:
- // Do we need to cancel the previous multi-block write?
- if (blockIndex != sdcard.multiWriteNextBlock) {
- if (sdcard_endWriteBlocks() == SDCARD_OPERATION_SUCCESS) {
- // Now we've entered the ready state, we can try again
- goto doMore;
- } else {
- return SDCARD_OPERATION_BUSY;
- }
- }
-
- // We're continuing a multi-block write
- break;
- case SDCARD_STATE_READY:
- // We're not continuing a multi-block write so we need to send a single-block write command
- sdcard_select();
-
- // Standard size cards use byte addressing, high capacity cards use block addressing
- status = sdcard_sendCommand(SDCARD_COMMAND_WRITE_BLOCK, sdcard.highCapacity ? blockIndex : blockIndex * SDCARD_BLOCK_SIZE);
-
- if (status != 0) {
- sdcard_deselect();
-
- sdcard_reset();
-
- return SDCARD_OPERATION_FAILURE;
- }
- break;
- default:
- return SDCARD_OPERATION_BUSY;
- }
-
- sdcard_sendDataBlockBegin(buffer, sdcard.state == SDCARD_STATE_WRITING_MULTIPLE_BLOCKS);
-
- sdcard.pendingOperation.buffer = buffer;
- sdcard.pendingOperation.blockIndex = blockIndex;
- sdcard.pendingOperation.callback = callback;
- sdcard.pendingOperation.callbackData = callbackData;
- sdcard.pendingOperation.chunkIndex = 1; // (for non-DMA transfers) we've sent chunk #0 already
- sdcard.state = SDCARD_STATE_SENDING_WRITE;
-
- return SDCARD_OPERATION_IN_PROGRESS;
-}
-
-/**
- * Begin writing a series of consecutive blocks beginning at the given block index. This will allow (but not require)
- * the SD card to pre-erase the number of blocks you specifiy, which can allow the writes to complete faster.
- *
- * Afterwards, just call sdcard_writeBlock() as normal to write those blocks consecutively.
- *
- * It's okay to abort the multi-block write at any time by writing to a non-consecutive address, or by performing a read.
- *
- * Returns:
- * SDCARD_OPERATION_SUCCESS - Multi-block write has been queued
- * SDCARD_OPERATION_BUSY - The card is already busy and cannot accept your write
- * SDCARD_OPERATION_FAILURE - A fatal error occured, card will be reset
- */
-sdcardOperationStatus_e sdcard_beginWriteBlocks(uint32_t blockIndex, uint32_t blockCount)
-{
- if (sdcard.state != SDCARD_STATE_READY) {
- if (sdcard.state == SDCARD_STATE_WRITING_MULTIPLE_BLOCKS) {
- if (blockIndex == sdcard.multiWriteNextBlock) {
- // Assume that the caller wants to continue the multi-block write they already have in progress!
- return SDCARD_OPERATION_SUCCESS;
- } else if (sdcard_endWriteBlocks() != SDCARD_OPERATION_SUCCESS) {
- return SDCARD_OPERATION_BUSY;
- } // Else we've completed the previous multi-block write and can fall through to start the new one
- } else {
- return SDCARD_OPERATION_BUSY;
- }
- }
-
- sdcard_select();
-
- if (
- sdcard_sendAppCommand(SDCARD_ACOMMAND_SET_WR_BLOCK_ERASE_COUNT, blockCount) == 0
- && sdcard_sendCommand(SDCARD_COMMAND_WRITE_MULTIPLE_BLOCK, sdcard.highCapacity ? blockIndex : blockIndex * SDCARD_BLOCK_SIZE) == 0
- ) {
- sdcard.state = SDCARD_STATE_WRITING_MULTIPLE_BLOCKS;
- sdcard.multiWriteBlocksRemain = blockCount;
- sdcard.multiWriteNextBlock = blockIndex;
-
- // Leave the card selected
- return SDCARD_OPERATION_SUCCESS;
- } else {
- sdcard_deselect();
-
- sdcard_reset();
-
- return SDCARD_OPERATION_FAILURE;
- }
-}
-
-/**
- * Read the 512-byte block with the given index into the given 512-byte buffer.
- *
- * When the read completes, your callback will be called. If the read was successful, the buffer pointer will be the
- * same buffer you originally passed in, otherwise the buffer will be set to NULL.
- *
- * You must keep the pointer to the buffer valid until the operation completes!
- *
- * Returns:
- * true - The operation was successfully queued for later completion, your callback will be called later
- * false - The operation could not be started due to the card being busy (try again later).
- */
-bool sdcard_readBlock(uint32_t blockIndex, uint8_t *buffer, sdcard_operationCompleteCallback_c callback, uint32_t callbackData)
-{
- if (sdcard.state != SDCARD_STATE_READY) {
- if (sdcard.state == SDCARD_STATE_WRITING_MULTIPLE_BLOCKS) {
- if (sdcard_endWriteBlocks() != SDCARD_OPERATION_SUCCESS) {
- return false;
- }
- } else {
- return false;
- }
- }
-
-#ifdef SDCARD_PROFILING
- sdcard.pendingOperation.profileStartTime = micros();
-#endif
-
- sdcard_select();
-
- // Standard size cards use byte addressing, high capacity cards use block addressing
- uint8_t status = sdcard_sendCommand(SDCARD_COMMAND_READ_SINGLE_BLOCK, sdcard.highCapacity ? blockIndex : blockIndex * SDCARD_BLOCK_SIZE);
-
- if (status == 0) {
- sdcard.pendingOperation.buffer = buffer;
- sdcard.pendingOperation.blockIndex = blockIndex;
- sdcard.pendingOperation.callback = callback;
- sdcard.pendingOperation.callbackData = callbackData;
-
- sdcard.state = SDCARD_STATE_READING;
-
- sdcard.operationStartTime = millis();
-
- // Leave the card selected for the whole transaction
-
- return true;
- } else {
- sdcard_deselect();
-
- return false;
- }
-}
-
-/**
- * Returns true if the SD card has successfully completed its startup procedures.
- */
-bool sdcard_isInitialized(void)
-{
- return sdcard.state >= SDCARD_STATE_READY;
-}
-
-const sdcardMetadata_t* sdcard_getMetadata(void)
-{
- return &sdcard.metadata;
-}
-
-#ifdef SDCARD_PROFILING
-
-void sdcard_setProfilerCallback(sdcard_profilerCallback_c callback)
-{
- sdcard.profiler = callback;
-}
-
-#endif
-
#endif
diff --git a/src/main/drivers/sdcard_impl.h b/src/main/drivers/sdcard_impl.h
new file mode 100644
index 0000000000..5a8374dd5c
--- /dev/null
+++ b/src/main/drivers/sdcard_impl.h
@@ -0,0 +1,113 @@
+/*
+ * 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 .
+ */
+
+#pragma once
+
+#include "drivers/nvic.h"
+#include "drivers/io.h"
+#include "dma.h"
+
+#include "drivers/bus_spi.h"
+#include "drivers/time.h"
+
+#include "sdcard.h"
+#include "sdcard_standard.h"
+
+#ifdef AFATFS_USE_INTROSPECTIVE_LOGGING
+ #define SDCARD_PROFILING
+#endif
+
+#define SDCARD_TIMEOUT_INIT_MILLIS 200
+#define SDCARD_MAX_CONSECUTIVE_FAILURES 8
+
+typedef enum {
+ // In these states we run at the initialization 400kHz clockspeed:
+ SDCARD_STATE_NOT_PRESENT = 0,
+ SDCARD_STATE_RESET,
+ SDCARD_STATE_CARD_INIT_IN_PROGRESS,
+ SDCARD_STATE_INITIALIZATION_RECEIVE_CID,
+
+ // In these states we run at full clock speed
+ SDCARD_STATE_READY,
+ SDCARD_STATE_READING,
+ SDCARD_STATE_SENDING_WRITE,
+ SDCARD_STATE_WAITING_FOR_WRITE,
+ SDCARD_STATE_WRITING_MULTIPLE_BLOCKS,
+ SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE
+} sdcardState_e;
+
+typedef struct sdcard_t {
+ struct {
+ uint8_t *buffer;
+ uint32_t blockIndex;
+ uint8_t chunkIndex;
+
+ sdcard_operationCompleteCallback_c callback;
+ uint32_t callbackData;
+
+#ifdef SDCARD_PROFILING
+ uint32_t profileStartTime;
+#endif
+ } pendingOperation;
+
+ uint32_t operationStartTime;
+
+ uint8_t failureCount;
+
+ uint8_t version;
+ bool highCapacity;
+
+ uint32_t multiWriteNextBlock;
+ uint32_t multiWriteBlocksRemain;
+
+ sdcardState_e state;
+
+ sdcardMetadata_t metadata;
+ sdcardCSD_t csd;
+
+#ifdef SDCARD_PROFILING
+ sdcard_profilerCallback_c profiler;
+#endif
+ bool enabled;
+ bool detectionInverted;
+ IO_t cardDetectPin;
+
+#ifdef USE_SDCARD_SPI
+ SPI_TypeDef *instance;
+ IO_t chipSelectPin;
+ bool useDMAForTx;
+ dmaChannelDescriptor_t * dma;
+#endif
+
+#ifdef USE_SDCARD_SDIO
+ dmaIdentifier_e dmaIdentifier;
+ uint8_t useCache;
+#endif
+
+ uint8_t dmaChannel;
+} sdcard_t;
+
+extern sdcard_t sdcard;
+
+STATIC_ASSERT(sizeof(sdcardCSD_t) == 16, sdcard_csd_bitfields_didnt_pack_properly);
+
+void sdcardInsertionDetectInit(void);
+void sdcardInsertionDetectDeinit(void);
+bool sdcard_isInserted(void);
diff --git a/src/main/drivers/sdcard_sdio_baremetal.c b/src/main/drivers/sdcard_sdio_baremetal.c
index 3e65845878..786b96006a 100644
--- a/src/main/drivers/sdcard_sdio_baremetal.c
+++ b/src/main/drivers/sdcard_sdio_baremetal.c
@@ -26,7 +26,6 @@
#include "platform.h"
-#define USE_SDCARD_SDIO
#ifdef USE_SDCARD_SDIO
#include "drivers/nvic.h"
@@ -36,6 +35,7 @@
#include "drivers/time.h"
#include "drivers/sdcard.h"
+#include "drivers/sdcard_impl.h"
#include "drivers/sdcard_standard.h"
#include "drivers/sdmmc_sdio.h"
@@ -43,13 +43,6 @@
#include "pg/pg.h"
#include "pg/sdio.h"
-#ifdef AFATFS_USE_INTROSPECTIVE_LOGGING
- #define SDCARD_PROFILING
-#endif
-
-#define SDCARD_TIMEOUT_INIT_MILLIS 200
-#define SDCARD_MAX_CONSECUTIVE_FAILURES 8
-
// Use this to speed up writing to SDCARD... asyncfatfs has limited support for multiblock write
#define FATFS_BLOCK_CACHE_SIZE 16
uint8_t writeCache[512 * FATFS_BLOCK_CACHE_SIZE] __attribute__ ((aligned (4)));
@@ -75,93 +68,6 @@ void cache_reset(void)
cacheCount = 0;
}
-typedef enum {
- // In these states we run at the initialization 400kHz clockspeed:
- SDCARD_STATE_NOT_PRESENT = 0,
- SDCARD_STATE_RESET,
- SDCARD_STATE_CARD_INIT_IN_PROGRESS,
- SDCARD_STATE_INITIALIZATION_RECEIVE_CID,
-
- // In these states we run at full clock speed
- SDCARD_STATE_READY,
- SDCARD_STATE_READING,
- SDCARD_STATE_SENDING_WRITE,
- SDCARD_STATE_WAITING_FOR_WRITE,
- SDCARD_STATE_WRITING_MULTIPLE_BLOCKS,
- SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE
-} sdcardState_e;
-
-typedef struct sdcard_t {
- struct {
- uint8_t *buffer;
- uint32_t blockIndex;
- uint8_t chunkIndex;
-
- sdcard_operationCompleteCallback_c callback;
- uint32_t callbackData;
-
-#ifdef SDCARD_PROFILING
- uint32_t profileStartTime;
-#endif
- } pendingOperation;
-
- uint32_t operationStartTime;
-
- uint8_t failureCount;
-
- uint8_t version;
- bool highCapacity;
-
- uint32_t multiWriteNextBlock;
- uint32_t multiWriteBlocksRemain;
-
- sdcardState_e state;
-
- sdcardMetadata_t metadata;
- sdcardCSD_t csd;
-
-#ifdef SDCARD_PROFILING
- sdcard_profilerCallback_c profiler;
-#endif
- bool enabled;
- IO_t cardDetectPin;
- dmaIdentifier_e dma;
- uint8_t dmaChannel;
- uint8_t useCache;
-} sdcard_t;
-
-static sdcard_t sdcard;
-
-STATIC_ASSERT(sizeof(sdcardCSD_t) == 16, sdcard_csd_bitfields_didnt_pack_properly);
-
-void sdcardInsertionDetectDeinit(void)
-{
- if (sdcard.cardDetectPin) {
- IOInit(sdcard.cardDetectPin, OWNER_FREE, 0);
- IOConfigGPIO(sdcard.cardDetectPin, IOCFG_IN_FLOATING);
- }
-}
-
-void sdcardInsertionDetectInit(void)
-{
- if (sdcard.cardDetectPin) {
- IOInit(sdcard.cardDetectPin, OWNER_SDCARD_DETECT, 0);
- IOConfigGPIO(sdcard.cardDetectPin, IOCFG_IPU);
- }
-}
-
-/**
- * Detect if a SD card is physically present in the memory slot.
- */
-bool sdcard_isInserted(void)
-{
- bool ret = true;
- if (sdcard.cardDetectPin) {
- ret = IORead(sdcard.cardDetectPin) == 0;
- }
- return ret;
-}
-
/**
* Returns true if the card has already been, or is currently, initializing and hasn't encountered enough errors to
* trip our error threshold and be disabled (i.e. our card is in and working!)
@@ -288,8 +194,8 @@ void sdcard_init(const sdcardConfig_t *config)
sdcard.state = SDCARD_STATE_NOT_PRESENT;
return;
}
- sdcard.dma = config->dmaIdentifier;
- if (sdcard.dma == 0) {
+ sdcard.dmaIdentifier = config->dmaIdentifier;
+ if (sdcard.dmaIdentifier == 0) {
sdcard.state = SDCARD_STATE_NOT_PRESENT;
return;
}
@@ -303,7 +209,7 @@ void sdcard_init(const sdcardConfig_t *config)
} else {
sdcard.useCache = 0;
}
- SD_Initialize_LL(dmaGetRefByIdentifier(sdcard.dma));
+ SD_Initialize_LL(dmaGetRefByIdentifier(sdcard.dmaIdentifier));
if (SD_IsDetected()) {
if (SD_Init() != 0) {
sdcard.state = SDCARD_STATE_NOT_PRESENT;
diff --git a/src/main/drivers/sdcard_spi.c b/src/main/drivers/sdcard_spi.c
new file mode 100644
index 0000000000..c2a8513376
--- /dev/null
+++ b/src/main/drivers/sdcard_spi.c
@@ -0,0 +1,1078 @@
+/*
+ * 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 .
+ */
+
+#include
+#include
+
+#include "platform.h"
+
+#ifdef USE_SDCARD_SPI
+
+#include "drivers/nvic.h"
+#include "drivers/io.h"
+#include "dma.h"
+
+#include "drivers/bus_spi.h"
+#include "drivers/time.h"
+
+#include "sdcard.h"
+#include "sdcard_impl.h"
+#include "sdcard_standard.h"
+
+#ifdef AFATFS_USE_INTROSPECTIVE_LOGGING
+ #define SDCARD_PROFILING
+#endif
+
+#define SET_CS_HIGH IOHi(sdcard.chipSelectPin)
+#define SET_CS_LOW IOLo(sdcard.chipSelectPin)
+
+#define SDCARD_INIT_NUM_DUMMY_BYTES 10
+#define SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY 8
+// Chosen so that CMD8 will have the same CRC as CMD0:
+#define SDCARD_IF_COND_CHECK_PATTERN 0xAB
+
+/* SPI_CLOCK_INITIALIZATION (256) is the slowest (Spec calls for under 400KHz) */
+#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER SPI_CLOCK_INITIALIZATION
+
+/* Operational speed <= 25MHz */
+#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER SPI_CLOCK_FAST
+
+/* Break up 512-byte SD card sectors into chunks of this size when writing without DMA to reduce the peak overhead
+ * per call to sdcard_poll().
+ */
+#define SDCARD_NON_DMA_CHUNK_SIZE 256
+
+/**
+ * Returns true if the card has already been, or is currently, initializing and hasn't encountered enough errors to
+ * trip our error threshold and be disabled (i.e. our card is in and working!)
+ */
+bool sdcard_isFunctional(void)
+{
+ return sdcard.state != SDCARD_STATE_NOT_PRESENT;
+}
+
+static void sdcard_select(void)
+{
+ SET_CS_LOW;
+}
+
+static void sdcard_deselect(void)
+{
+ // As per the SD-card spec, give the card 8 dummy clocks so it can finish its operation
+ //spiTransferByte(sdcard.instance, 0xFF);
+
+ while (spiIsBusBusy(sdcard.instance)) {
+ }
+
+ SET_CS_HIGH;
+}
+
+/**
+ * Handle a failure of an SD card operation by resetting the card back to its initialization phase.
+ *
+ * Increments the failure counter, and when the failure threshold is reached, disables the card until
+ * the next call to sdcard_init().
+ */
+static void sdcard_reset(void)
+{
+ if (!sdcard_isInserted()) {
+ sdcard.state = SDCARD_STATE_NOT_PRESENT;
+ return;
+ }
+
+ if (sdcard.state >= SDCARD_STATE_READY) {
+ spiSetDivisor(sdcard.instance, SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER);
+ }
+
+ sdcard.failureCount++;
+ if (sdcard.failureCount >= SDCARD_MAX_CONSECUTIVE_FAILURES) {
+ sdcard.state = SDCARD_STATE_NOT_PRESENT;
+ } else {
+ sdcard.operationStartTime = millis();
+ sdcard.state = SDCARD_STATE_RESET;
+ }
+}
+
+/**
+ * The SD card spec requires 8 clock cycles to be sent by us on the bus after most commands so it can finish its
+ * processing of that command. The easiest way for us to do this is to just wait for the bus to become idle before
+ * we transmit a command, sending at least 8-bits onto the bus when we do so.
+ */
+static bool sdcard_waitForIdle(int maxBytesToWait)
+{
+ while (maxBytesToWait > 0) {
+ uint8_t b = spiTransferByte(sdcard.instance, 0xFF);
+ if (b == 0xFF) {
+ return true;
+ }
+ maxBytesToWait--;
+ }
+
+ return false;
+}
+
+/**
+ * Wait for up to maxDelay 0xFF idle bytes to arrive from the card, returning the first non-idle byte found.
+ *
+ * Returns 0xFF on failure.
+ */
+static uint8_t sdcard_waitForNonIdleByte(int maxDelay)
+{
+ for (int i = 0; i < maxDelay + 1; i++) { // + 1 so we can wait for maxDelay '0xFF' bytes before reading a response byte afterwards
+ uint8_t response = spiTransferByte(sdcard.instance, 0xFF);
+
+ if (response != 0xFF) {
+ return response;
+ }
+ }
+
+ return 0xFF;
+}
+
+/**
+ * Waits up to SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY bytes for the card to become ready, send a command to the card
+ * with the given argument, waits up to SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY bytes for a reply, and returns the
+ * first non-0xFF byte of the reply.
+ *
+ * You must select the card first with sdcard_select() and deselect it afterwards with sdcard_deselect().
+ *
+ * Upon failure, 0xFF is returned.
+ */
+static uint8_t sdcard_sendCommand(uint8_t commandCode, uint32_t commandArgument)
+{
+ const uint8_t command[6] = {
+ 0x40 | commandCode,
+ commandArgument >> 24,
+ commandArgument >> 16,
+ commandArgument >> 8,
+ commandArgument,
+ 0x95 /* Static CRC. This CRC is valid for CMD0 with a 0 argument, and CMD8 with 0x1AB argument, which are the only
+ commands that require a CRC */
+ };
+
+ // Go ahead and send the command even if the card isn't idle if this is the reset command
+ if (!sdcard_waitForIdle(SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY) && commandCode != SDCARD_COMMAND_GO_IDLE_STATE)
+ return 0xFF;
+
+ spiTransfer(sdcard.instance, command, NULL, sizeof(command));
+
+ /*
+ * The card can take up to SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY bytes to send the response, in the meantime
+ * it'll transmit 0xFF filler bytes.
+ */
+ return sdcard_waitForNonIdleByte(SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY);
+}
+
+static uint8_t sdcard_sendAppCommand(uint8_t commandCode, uint32_t commandArgument)
+{
+ sdcard_sendCommand(SDCARD_COMMAND_APP_CMD, 0);
+
+ return sdcard_sendCommand(commandCode, commandArgument);
+}
+
+/**
+ * Sends an IF_COND message to the card to check its version and validate its voltage requirements. Sets the global
+ * sdCardVersion with the detected version (0, 1, or 2) and returns true if the card is compatible.
+ */
+static bool sdcard_validateInterfaceCondition(void)
+{
+ uint8_t ifCondReply[4];
+
+ sdcard.version = 0;
+
+ sdcard_select();
+
+ uint8_t status = sdcard_sendCommand(SDCARD_COMMAND_SEND_IF_COND, (SDCARD_VOLTAGE_ACCEPTED_2_7_to_3_6 << 8) | SDCARD_IF_COND_CHECK_PATTERN);
+
+ // Don't deselect the card right away, because we'll want to read the rest of its reply if it's a V2 card
+
+ if (status == (SDCARD_R1_STATUS_BIT_ILLEGAL_COMMAND | SDCARD_R1_STATUS_BIT_IDLE)) {
+ // V1 cards don't support this command
+ sdcard.version = 1;
+ } else if (status == SDCARD_R1_STATUS_BIT_IDLE) {
+ spiTransfer(sdcard.instance, NULL, ifCondReply, sizeof(ifCondReply));
+
+ /*
+ * We don't bother to validate the SDCard's operating voltage range since the spec requires it to accept our
+ * 3.3V, but do check that it echoed back our check pattern properly.
+ */
+ if (ifCondReply[3] == SDCARD_IF_COND_CHECK_PATTERN) {
+ sdcard.version = 2;
+ }
+ }
+
+ sdcard_deselect();
+
+ return sdcard.version > 0;
+}
+
+static bool sdcard_readOCRRegister(uint32_t *result)
+{
+ sdcard_select();
+
+ uint8_t status = sdcard_sendCommand(SDCARD_COMMAND_READ_OCR, 0);
+
+ uint8_t response[4];
+
+ spiTransfer(sdcard.instance, NULL, response, sizeof(response));
+
+ if (status == 0) {
+ sdcard_deselect();
+
+ *result = (response[0] << 24) | (response[1] << 16) | (response[2] << 8) | response[3];
+
+ return true;
+ } else {
+ sdcard_deselect();
+
+ return false;
+ }
+}
+
+typedef enum {
+ SDCARD_RECEIVE_SUCCESS,
+ SDCARD_RECEIVE_BLOCK_IN_PROGRESS,
+ SDCARD_RECEIVE_ERROR
+} sdcardReceiveBlockStatus_e;
+
+/**
+ * Attempt to receive a data block from the SD card.
+ *
+ * Return true on success, otherwise the card has not responded yet and you should retry later.
+ */
+static sdcardReceiveBlockStatus_e sdcard_receiveDataBlock(uint8_t *buffer, int count)
+{
+ uint8_t dataToken = sdcard_waitForNonIdleByte(8);
+
+ if (dataToken == 0xFF) {
+ return SDCARD_RECEIVE_BLOCK_IN_PROGRESS;
+ }
+
+ if (dataToken != SDCARD_SINGLE_BLOCK_READ_START_TOKEN) {
+ return SDCARD_RECEIVE_ERROR;
+ }
+
+ spiTransfer(sdcard.instance, NULL, buffer, count);
+
+ // Discard trailing CRC, we don't care
+ spiTransferByte(sdcard.instance, 0xFF);
+ spiTransferByte(sdcard.instance, 0xFF);
+
+ return SDCARD_RECEIVE_SUCCESS;
+}
+
+static bool sdcard_sendDataBlockFinish(void)
+{
+#ifdef USE_HAL_DRIVER
+ // Drain anything left in the Rx FIFO (we didn't read it during the write)
+ //This is necessary here as when using msc there is timing issue
+ while (LL_SPI_IsActiveFlag_RXNE(sdcard.instance)) {
+ sdcard.instance->DR;
+ }
+#endif
+
+ // Send a dummy CRC
+ spiTransferByte(sdcard.instance, 0x00);
+ spiTransferByte(sdcard.instance, 0x00);
+
+ uint8_t dataResponseToken = spiTransferByte(sdcard.instance, 0xFF);
+
+ /*
+ * Check if the card accepted the write (no CRC error / no address error)
+ *
+ * The lower 5 bits are structured as follows:
+ * | 0 | Status | 1 |
+ * | 0 | x x x | 1 |
+ *
+ * Statuses:
+ * 010 - Data accepted
+ * 101 - CRC error
+ * 110 - Write error
+ */
+ return (dataResponseToken & 0x1F) == 0x05;
+}
+
+/**
+ * Begin sending a buffer of SDCARD_BLOCK_SIZE bytes to the SD card.
+ */
+static void sdcard_sendDataBlockBegin(const uint8_t *buffer, bool multiBlockWrite)
+{
+ // Card wants 8 dummy clock cycles between the write command's response and a data block beginning:
+ spiTransferByte(sdcard.instance, 0xFF);
+
+ spiTransferByte(sdcard.instance, multiBlockWrite ? SDCARD_MULTIPLE_BLOCK_WRITE_START_TOKEN : SDCARD_SINGLE_BLOCK_WRITE_START_TOKEN);
+
+ if (sdcard.useDMAForTx) {
+#if defined(USE_HAL_DRIVER)
+ LL_DMA_InitTypeDef init;
+
+ LL_DMA_StructInit(&init);
+
+ init.Channel = dmaGetChannel(sdcard.dmaChannel);
+ init.Mode = LL_DMA_MODE_NORMAL;
+ init.Direction = LL_DMA_DIRECTION_MEMORY_TO_PERIPH;
+
+ init.PeriphOrM2MSrcAddress = (uint32_t)&sdcard.instance->DR;
+ init.Priority = LL_DMA_PRIORITY_LOW;
+ init.PeriphOrM2MSrcIncMode = LL_DMA_PERIPH_NOINCREMENT;
+ init.PeriphOrM2MSrcDataSize = LL_DMA_PDATAALIGN_BYTE;
+
+ init.MemoryOrM2MDstAddress = (uint32_t)buffer;
+ init.MemoryOrM2MDstIncMode = LL_DMA_MEMORY_INCREMENT;
+ init.MemoryOrM2MDstDataSize = LL_DMA_MDATAALIGN_BYTE;
+
+ init.NbData = SDCARD_BLOCK_SIZE;
+
+ LL_DMA_DeInit(sdcard.dma->dma, sdcard.dma->stream);
+ LL_DMA_Init(sdcard.dma->dma, sdcard.dma->stream, &init);
+
+ LL_DMA_EnableStream(sdcard.dma->dma, sdcard.dma->stream);
+
+ LL_SPI_EnableDMAReq_TX(sdcard.instance);
+
+#else
+
+ DMA_InitTypeDef init;
+
+ DMA_StructInit(&init);
+#ifdef STM32F4
+ init.DMA_Channel = dmaGetChannel(sdcard.dmaChannel);
+ init.DMA_Memory0BaseAddr = (uint32_t) buffer;
+ init.DMA_DIR = DMA_DIR_MemoryToPeripheral;
+#else
+ init.DMA_M2M = DMA_M2M_Disable;
+ init.DMA_MemoryBaseAddr = (uint32_t) buffer;
+ init.DMA_DIR = DMA_DIR_PeripheralDST;
+#endif
+ init.DMA_PeripheralBaseAddr = (uint32_t) &sdcard.instance->DR;
+ init.DMA_Priority = DMA_Priority_Low;
+ init.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ init.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
+
+ init.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ init.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
+
+ init.DMA_BufferSize = SDCARD_BLOCK_SIZE;
+ init.DMA_Mode = DMA_Mode_Normal;
+
+ DMA_DeInit(sdcard.dma->ref);
+ DMA_Init(sdcard.dma->ref, &init);
+
+ DMA_Cmd(sdcard.dma->ref, ENABLE);
+
+ SPI_I2S_DMACmd(sdcard.instance, SPI_I2S_DMAReq_Tx, ENABLE);
+#endif
+ } else {
+ // Send the first chunk now
+ spiTransfer(sdcard.instance, buffer, NULL, SDCARD_NON_DMA_CHUNK_SIZE);
+ }
+}
+
+static bool sdcard_receiveCID(void)
+{
+ uint8_t cid[16];
+
+ if (sdcard_receiveDataBlock(cid, sizeof(cid)) != SDCARD_RECEIVE_SUCCESS) {
+ return false;
+ }
+
+ sdcard.metadata.manufacturerID = cid[0];
+ sdcard.metadata.oemID = (cid[1] << 8) | cid[2];
+ sdcard.metadata.productName[0] = cid[3];
+ sdcard.metadata.productName[1] = cid[4];
+ sdcard.metadata.productName[2] = cid[5];
+ sdcard.metadata.productName[3] = cid[6];
+ sdcard.metadata.productName[4] = cid[7];
+ sdcard.metadata.productRevisionMajor = cid[8] >> 4;
+ sdcard.metadata.productRevisionMinor = cid[8] & 0x0F;
+ sdcard.metadata.productSerial = (cid[9] << 24) | (cid[10] << 16) | (cid[11] << 8) | cid[12];
+ sdcard.metadata.productionYear = (((cid[13] & 0x0F) << 4) | (cid[14] >> 4)) + 2000;
+ sdcard.metadata.productionMonth = cid[14] & 0x0F;
+
+ return true;
+}
+
+static bool sdcard_fetchCSD(void)
+{
+ uint32_t readBlockLen, blockCount, blockCountMult;
+ uint64_t capacityBytes;
+
+ sdcard_select();
+
+ /* The CSD command's data block should always arrive within 8 idle clock cycles (SD card spec). This is because
+ * the information about card latency is stored in the CSD register itself, so we can't use that yet!
+ */
+ bool success =
+ sdcard_sendCommand(SDCARD_COMMAND_SEND_CSD, 0) == 0
+ && sdcard_receiveDataBlock((uint8_t*) &sdcard.csd, sizeof(sdcard.csd)) == SDCARD_RECEIVE_SUCCESS
+ && SDCARD_GET_CSD_FIELD(sdcard.csd, 1, TRAILER) == 1;
+
+ if (success) {
+ switch (SDCARD_GET_CSD_FIELD(sdcard.csd, 1, CSD_STRUCTURE_VER)) {
+ case SDCARD_CSD_STRUCTURE_VERSION_1:
+ // Block size in bytes (doesn't have to be 512)
+ readBlockLen = 1 << SDCARD_GET_CSD_FIELD(sdcard.csd, 1, READ_BLOCK_LEN);
+ blockCountMult = 1 << (SDCARD_GET_CSD_FIELD(sdcard.csd, 1, CSIZE_MULT) + 2);
+ blockCount = (SDCARD_GET_CSD_FIELD(sdcard.csd, 1, CSIZE) + 1) * blockCountMult;
+
+ // We could do this in 32 bits but it makes the 2GB case awkward
+ capacityBytes = (uint64_t) blockCount * readBlockLen;
+
+ // Re-express that capacity (max 2GB) in our standard 512-byte block size
+ sdcard.metadata.numBlocks = capacityBytes / SDCARD_BLOCK_SIZE;
+ break;
+ case SDCARD_CSD_STRUCTURE_VERSION_2:
+ sdcard.metadata.numBlocks = (SDCARD_GET_CSD_FIELD(sdcard.csd, 2, CSIZE) + 1) * 1024;
+ break;
+ default:
+ success = false;
+ }
+ }
+
+ sdcard_deselect();
+
+ return success;
+}
+
+/**
+ * Check if the SD Card has completed its startup sequence. Must be called with sdcard.state == SDCARD_STATE_INITIALIZATION.
+ *
+ * Returns true if the card has finished its init process.
+ */
+static bool sdcard_checkInitDone(void)
+{
+ sdcard_select();
+
+ uint8_t status = sdcard_sendAppCommand(SDCARD_ACOMMAND_SEND_OP_COND, sdcard.version == 2 ? 1 << 30 /* We support high capacity cards */ : 0);
+
+ sdcard_deselect();
+
+ // When card init is complete, the idle bit in the response becomes zero.
+ return status == 0x00;
+}
+
+/**
+ * Begin the initialization process for the SD card. This must be called first before any other sdcard_ routine.
+ */
+void sdcard_init(const sdcardConfig_t *config)
+{
+ sdcard.enabled = config->enabled;
+ if (!sdcard.enabled) {
+ sdcard.state = SDCARD_STATE_NOT_PRESENT;
+ return;
+ }
+
+ sdcard.instance = spiInstanceByDevice(SPI_CFG_TO_DEV(config->device));
+
+ sdcard.useDMAForTx = config->useDma;
+ if (sdcard.useDMAForTx) {
+#if defined(STM32F4) || defined(STM32F7)
+ sdcard.dmaChannel = config->dmaChannel;
+#endif
+ sdcard.dma = dmaGetDescriptorByIdentifier(config->dmaIdentifier);
+ dmaInit(config->dmaIdentifier, OWNER_SDCARD, 0);
+ }
+
+ if (config->chipSelectTag) {
+ sdcard.chipSelectPin = IOGetByTag(config->chipSelectTag);
+ IOInit(sdcard.chipSelectPin, OWNER_SDCARD_CS, 0);
+ IOConfigGPIO(sdcard.chipSelectPin, SPI_IO_CS_CFG);
+ } else {
+ sdcard.chipSelectPin = IO_NONE;
+ }
+
+ if (config->cardDetectTag) {
+ sdcard.cardDetectPin = IOGetByTag(config->cardDetectTag);
+ sdcard.detectionInverted = config->cardDetectInverted;
+ } else {
+ sdcard.cardDetectPin = IO_NONE;
+ sdcard.detectionInverted = false;
+ }
+
+ // Max frequency is initially 400kHz
+ spiSetDivisor(sdcard.instance, SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER);
+
+ // SDCard wants 1ms minimum delay after power is applied to it
+ delay(1000);
+
+ // Transmit at least 74 dummy clock cycles with CS high so the SD card can start up
+ SET_CS_HIGH;
+
+ spiTransfer(sdcard.instance, NULL, NULL, SDCARD_INIT_NUM_DUMMY_BYTES);
+
+ // Wait for that transmission to finish before we enable the SDCard, so it receives the required number of cycles:
+ int time = 100000;
+ while (spiIsBusBusy(sdcard.instance)) {
+ if (time-- == 0) {
+ sdcard.state = SDCARD_STATE_NOT_PRESENT;
+ sdcard.failureCount++;
+ return;
+ }
+ }
+
+ sdcard.operationStartTime = millis();
+ sdcard.state = SDCARD_STATE_RESET;
+ sdcard.failureCount = 0;
+}
+
+static bool sdcard_setBlockLength(uint32_t blockLen)
+{
+ sdcard_select();
+
+ uint8_t status = sdcard_sendCommand(SDCARD_COMMAND_SET_BLOCKLEN, blockLen);
+
+ sdcard_deselect();
+
+ return status == 0;
+}
+
+/*
+ * Returns true if the card is ready to accept read/write commands.
+ */
+static bool sdcard_isReady(void)
+{
+ return sdcard.state == SDCARD_STATE_READY || sdcard.state == SDCARD_STATE_WRITING_MULTIPLE_BLOCKS;
+}
+
+/**
+ * Send the stop-transmission token to complete a multi-block write.
+ *
+ * Returns:
+ * SDCARD_OPERATION_IN_PROGRESS - We're now waiting for that stop to complete, the card will enter
+ * the SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE state.
+ * SDCARD_OPERATION_SUCCESS - The multi-block write finished immediately, the card will enter
+ * the SDCARD_READY state.
+ *
+ */
+static sdcardOperationStatus_e sdcard_endWriteBlocks(void)
+{
+ sdcard.multiWriteBlocksRemain = 0;
+
+ // 8 dummy clocks to guarantee N_WR clocks between the last card response and this token
+ spiTransferByte(sdcard.instance, 0xFF);
+
+ spiTransferByte(sdcard.instance, SDCARD_MULTIPLE_BLOCK_WRITE_STOP_TOKEN);
+
+ // Card may choose to raise a busy (non-0xFF) signal after at most N_BR (1 byte) delay
+ if (sdcard_waitForNonIdleByte(1) == 0xFF) {
+ sdcard.state = SDCARD_STATE_READY;
+ return SDCARD_OPERATION_SUCCESS;
+ } else {
+ sdcard.state = SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE;
+ sdcard.operationStartTime = millis();
+
+ return SDCARD_OPERATION_IN_PROGRESS;
+ }
+}
+
+/**
+ * Call periodically for the SD card to perform in-progress transfers.
+ *
+ * Returns true if the card is ready to accept commands.
+ */
+bool sdcard_poll(void)
+{
+ if (!sdcard.enabled) {
+ sdcard.state = SDCARD_STATE_NOT_PRESENT;
+ return false;
+ }
+
+ uint8_t initStatus;
+ bool sendComplete;
+
+#ifdef SDCARD_PROFILING
+ bool profilingComplete;
+#endif
+
+ doMore:
+ switch (sdcard.state) {
+ case SDCARD_STATE_RESET:
+ sdcard_select();
+
+ initStatus = sdcard_sendCommand(SDCARD_COMMAND_GO_IDLE_STATE, 0);
+
+ sdcard_deselect();
+
+ if (initStatus == SDCARD_R1_STATUS_BIT_IDLE) {
+ // Check card voltage and version
+ if (sdcard_validateInterfaceCondition()) {
+
+ sdcard.state = SDCARD_STATE_CARD_INIT_IN_PROGRESS;
+ goto doMore;
+ } else {
+ // Bad reply/voltage, we ought to refrain from accessing the card.
+ sdcard.state = SDCARD_STATE_NOT_PRESENT;
+ }
+ }
+ break;
+
+ case SDCARD_STATE_CARD_INIT_IN_PROGRESS:
+ if (sdcard_checkInitDone()) {
+ if (sdcard.version == 2) {
+ // Check for high capacity card
+ uint32_t ocr;
+
+ if (!sdcard_readOCRRegister(&ocr)) {
+ sdcard_reset();
+ goto doMore;
+ }
+
+ sdcard.highCapacity = (ocr & (1 << 30)) != 0;
+ } else {
+ // Version 1 cards are always low-capacity
+ sdcard.highCapacity = false;
+ }
+
+ // Now fetch the CSD and CID registers
+ if (sdcard_fetchCSD()) {
+ sdcard_select();
+
+ uint8_t status = sdcard_sendCommand(SDCARD_COMMAND_SEND_CID, 0);
+
+ if (status == 0) {
+ // Keep the card selected to receive the response block
+ sdcard.state = SDCARD_STATE_INITIALIZATION_RECEIVE_CID;
+ goto doMore;
+ } else {
+ sdcard_deselect();
+
+ sdcard_reset();
+ goto doMore;
+ }
+ }
+ }
+ break;
+ case SDCARD_STATE_INITIALIZATION_RECEIVE_CID:
+ if (sdcard_receiveCID()) {
+ sdcard_deselect();
+
+ /* The spec is a little iffy on what the default block size is for Standard Size cards (it can be changed on
+ * standard size cards) so let's just set it to 512 explicitly so we don't have a problem.
+ */
+ if (!sdcard.highCapacity && !sdcard_setBlockLength(SDCARD_BLOCK_SIZE)) {
+ sdcard_reset();
+ goto doMore;
+ }
+
+ // Now we're done with init and we can switch to the full speed clock (<25MHz)
+ spiSetDivisor(sdcard.instance, SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER);
+
+ sdcard.multiWriteBlocksRemain = 0;
+
+ sdcard.state = SDCARD_STATE_READY;
+ goto doMore;
+ } // else keep waiting for the CID to arrive
+ break;
+ case SDCARD_STATE_SENDING_WRITE:
+ // Have we finished sending the write yet?
+ sendComplete = false;
+
+#if defined(USE_HAL_DRIVER)
+ if (sdcard.useDMAForTx && DMA_GET_FLAG_STATUS(sdcard.dma, DMA_IT_TCIF)) {
+ //Clear both flags after transfer
+ DMA_CLEAR_FLAG(sdcard.dma, DMA_IT_TCIF);
+ DMA_CLEAR_FLAG(sdcard.dma, DMA_IT_HTIF);
+ // Drain anything left in the Rx FIFO (we didn't read it during the write)
+ while (LL_SPI_IsActiveFlag_RXNE(sdcard.instance)) {
+ sdcard.instance->DR;
+ }
+
+ // Wait for the final bit to be transmitted
+ while (spiIsBusBusy(sdcard.instance)) {
+ }
+
+ LL_SPI_DisableDMAReq_TX(sdcard.instance);
+
+ sendComplete = true;
+ }
+#else
+#ifdef STM32F4
+ if (sdcard.useDMAForTx && DMA_GetFlagStatus(sdcard.dma->ref, sdcard.dma->completeFlag) == SET) {
+ DMA_ClearFlag(sdcard.dma->ref, sdcard.dma->completeFlag);
+#else
+ if (sdcard.useDMAForTx && DMA_GetFlagStatus(sdcard.dma->completeFlag) == SET) {
+ DMA_ClearFlag(sdcard.dma->completeFlag);
+#endif
+
+ DMA_Cmd(sdcard.dma->ref, DISABLE);
+
+ // Drain anything left in the Rx FIFO (we didn't read it during the write)
+ while (SPI_I2S_GetFlagStatus(sdcard.instance, SPI_I2S_FLAG_RXNE) == SET) {
+ sdcard.instance->DR;
+ }
+
+ // Wait for the final bit to be transmitted
+ while (spiIsBusBusy(sdcard.instance)) {
+ }
+
+ SPI_I2S_DMACmd(sdcard.instance, SPI_I2S_DMAReq_Tx, DISABLE);
+
+ sendComplete = true;
+ }
+#endif
+ if (!sdcard.useDMAForTx) {
+ // Send another chunk
+ spiTransfer(sdcard.instance, sdcard.pendingOperation.buffer + SDCARD_NON_DMA_CHUNK_SIZE * sdcard.pendingOperation.chunkIndex, NULL, SDCARD_NON_DMA_CHUNK_SIZE);
+
+ sdcard.pendingOperation.chunkIndex++;
+
+ sendComplete = sdcard.pendingOperation.chunkIndex == SDCARD_BLOCK_SIZE / SDCARD_NON_DMA_CHUNK_SIZE;
+ }
+
+ if (sendComplete) {
+ // Finish up by sending the CRC and checking the SD-card's acceptance/rejectance
+ if (sdcard_sendDataBlockFinish()) {
+ // The SD card is now busy committing that write to the card
+ sdcard.state = SDCARD_STATE_WAITING_FOR_WRITE;
+ sdcard.operationStartTime = millis();
+
+ // Since we've transmitted the buffer we can go ahead and tell the caller their operation is complete
+ if (sdcard.pendingOperation.callback) {
+ sdcard.pendingOperation.callback(SDCARD_BLOCK_OPERATION_WRITE, sdcard.pendingOperation.blockIndex, sdcard.pendingOperation.buffer, sdcard.pendingOperation.callbackData);
+ }
+ } else {
+ /* Our write was rejected! This could be due to a bad address but we hope not to attempt that, so assume
+ * the card is broken and needs reset.
+ */
+ sdcard_reset();
+
+ // Announce write failure:
+ if (sdcard.pendingOperation.callback) {
+ sdcard.pendingOperation.callback(SDCARD_BLOCK_OPERATION_WRITE, sdcard.pendingOperation.blockIndex, NULL, sdcard.pendingOperation.callbackData);
+ }
+
+ goto doMore;
+ }
+ }
+ break;
+ case SDCARD_STATE_WAITING_FOR_WRITE:
+ if (sdcard_waitForIdle(SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY)) {
+#ifdef SDCARD_PROFILING
+ profilingComplete = true;
+#endif
+
+ sdcard.failureCount = 0; // Assume the card is good if it can complete a write
+
+ // Still more blocks left to write in a multi-block chain?
+ if (sdcard.multiWriteBlocksRemain > 1) {
+ sdcard.multiWriteBlocksRemain--;
+ sdcard.multiWriteNextBlock++;
+ sdcard.state = SDCARD_STATE_WRITING_MULTIPLE_BLOCKS;
+ } else if (sdcard.multiWriteBlocksRemain == 1) {
+ // This function changes the sd card state for us whether immediately succesful or delayed:
+ if (sdcard_endWriteBlocks() == SDCARD_OPERATION_SUCCESS) {
+ sdcard_deselect();
+ } else {
+#ifdef SDCARD_PROFILING
+ // Wait for the multi-block write to be terminated before finishing timing
+ profilingComplete = false;
+#endif
+ }
+ } else {
+ sdcard.state = SDCARD_STATE_READY;
+ sdcard_deselect();
+ }
+
+#ifdef SDCARD_PROFILING
+ if (profilingComplete && sdcard.profiler) {
+ sdcard.profiler(SDCARD_BLOCK_OPERATION_WRITE, sdcard.pendingOperation.blockIndex, micros() - sdcard.pendingOperation.profileStartTime);
+ }
+#endif
+ } else if (millis() > sdcard.operationStartTime + SDCARD_TIMEOUT_WRITE_MSEC) {
+ /*
+ * The caller has already been told that their write has completed, so they will have discarded
+ * their buffer and have no hope of retrying the operation. But this should be very rare and it allows
+ * them to reuse their buffer milliseconds faster than they otherwise would.
+ */
+ sdcard_reset();
+ goto doMore;
+ }
+ break;
+ case SDCARD_STATE_READING:
+ switch (sdcard_receiveDataBlock(sdcard.pendingOperation.buffer, SDCARD_BLOCK_SIZE)) {
+ case SDCARD_RECEIVE_SUCCESS:
+ sdcard_deselect();
+
+ sdcard.state = SDCARD_STATE_READY;
+ sdcard.failureCount = 0; // Assume the card is good if it can complete a read
+
+#ifdef SDCARD_PROFILING
+ if (sdcard.profiler) {
+ sdcard.profiler(SDCARD_BLOCK_OPERATION_READ, sdcard.pendingOperation.blockIndex, micros() - sdcard.pendingOperation.profileStartTime);
+ }
+#endif
+
+ if (sdcard.pendingOperation.callback) {
+ sdcard.pendingOperation.callback(
+ SDCARD_BLOCK_OPERATION_READ,
+ sdcard.pendingOperation.blockIndex,
+ sdcard.pendingOperation.buffer,
+ sdcard.pendingOperation.callbackData
+ );
+ }
+ break;
+ case SDCARD_RECEIVE_BLOCK_IN_PROGRESS:
+ if (millis() <= sdcard.operationStartTime + SDCARD_TIMEOUT_READ_MSEC) {
+ break; // Timeout not reached yet so keep waiting
+ }
+ // Timeout has expired, so fall through to convert to a fatal error
+ FALLTHROUGH;
+
+ case SDCARD_RECEIVE_ERROR:
+ sdcard_deselect();
+
+ sdcard_reset();
+
+ if (sdcard.pendingOperation.callback) {
+ sdcard.pendingOperation.callback(
+ SDCARD_BLOCK_OPERATION_READ,
+ sdcard.pendingOperation.blockIndex,
+ NULL,
+ sdcard.pendingOperation.callbackData
+ );
+ }
+
+ goto doMore;
+ break;
+ }
+ break;
+ case SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE:
+ if (sdcard_waitForIdle(SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY)) {
+ sdcard_deselect();
+
+ sdcard.state = SDCARD_STATE_READY;
+
+#ifdef SDCARD_PROFILING
+ if (sdcard.profiler) {
+ sdcard.profiler(SDCARD_BLOCK_OPERATION_WRITE, sdcard.pendingOperation.blockIndex, micros() - sdcard.pendingOperation.profileStartTime);
+ }
+#endif
+ } else if (millis() > sdcard.operationStartTime + SDCARD_TIMEOUT_WRITE_MSEC) {
+ sdcard_reset();
+ goto doMore;
+ }
+ break;
+ case SDCARD_STATE_NOT_PRESENT:
+ default:
+ ;
+ }
+
+ // Is the card's initialization taking too long?
+ if (sdcard.state >= SDCARD_STATE_RESET && sdcard.state < SDCARD_STATE_READY
+ && millis() - sdcard.operationStartTime > SDCARD_TIMEOUT_INIT_MILLIS) {
+ sdcard_reset();
+ }
+
+ return sdcard_isReady();
+}
+
+/**
+ * Write the 512-byte block from the given buffer into the block with the given index.
+ *
+ * If the write does not complete immediately, your callback will be called later. If the write was successful, the
+ * buffer pointer will be the same buffer you originally passed in, otherwise the buffer will be set to NULL.
+ *
+ * Returns:
+ * SDCARD_OPERATION_IN_PROGRESS - Your buffer is currently being transmitted to the card and your callback will be
+ * called later to report the completion. The buffer pointer must remain valid until
+ * that time.
+ * SDCARD_OPERATION_SUCCESS - Your buffer has been transmitted to the card now.
+ * SDCARD_OPERATION_BUSY - The card is already busy and cannot accept your write
+ * SDCARD_OPERATION_FAILURE - Your write was rejected by the card, card will be reset
+ */
+sdcardOperationStatus_e sdcard_writeBlock(uint32_t blockIndex, uint8_t *buffer, sdcard_operationCompleteCallback_c callback, uint32_t callbackData)
+{
+ uint8_t status;
+
+#ifdef SDCARD_PROFILING
+ sdcard.pendingOperation.profileStartTime = micros();
+#endif
+
+ doMore:
+ switch (sdcard.state) {
+ case SDCARD_STATE_WRITING_MULTIPLE_BLOCKS:
+ // Do we need to cancel the previous multi-block write?
+ if (blockIndex != sdcard.multiWriteNextBlock) {
+ if (sdcard_endWriteBlocks() == SDCARD_OPERATION_SUCCESS) {
+ // Now we've entered the ready state, we can try again
+ goto doMore;
+ } else {
+ return SDCARD_OPERATION_BUSY;
+ }
+ }
+
+ // We're continuing a multi-block write
+ break;
+ case SDCARD_STATE_READY:
+ // We're not continuing a multi-block write so we need to send a single-block write command
+ sdcard_select();
+
+ // Standard size cards use byte addressing, high capacity cards use block addressing
+ status = sdcard_sendCommand(SDCARD_COMMAND_WRITE_BLOCK, sdcard.highCapacity ? blockIndex : blockIndex * SDCARD_BLOCK_SIZE);
+
+ if (status != 0) {
+ sdcard_deselect();
+
+ sdcard_reset();
+
+ return SDCARD_OPERATION_FAILURE;
+ }
+ break;
+ default:
+ return SDCARD_OPERATION_BUSY;
+ }
+
+ sdcard_sendDataBlockBegin(buffer, sdcard.state == SDCARD_STATE_WRITING_MULTIPLE_BLOCKS);
+
+ sdcard.pendingOperation.buffer = buffer;
+ sdcard.pendingOperation.blockIndex = blockIndex;
+ sdcard.pendingOperation.callback = callback;
+ sdcard.pendingOperation.callbackData = callbackData;
+ sdcard.pendingOperation.chunkIndex = 1; // (for non-DMA transfers) we've sent chunk #0 already
+ sdcard.state = SDCARD_STATE_SENDING_WRITE;
+
+ return SDCARD_OPERATION_IN_PROGRESS;
+}
+
+/**
+ * Begin writing a series of consecutive blocks beginning at the given block index. This will allow (but not require)
+ * the SD card to pre-erase the number of blocks you specifiy, which can allow the writes to complete faster.
+ *
+ * Afterwards, just call sdcard_writeBlock() as normal to write those blocks consecutively.
+ *
+ * It's okay to abort the multi-block write at any time by writing to a non-consecutive address, or by performing a read.
+ *
+ * Returns:
+ * SDCARD_OPERATION_SUCCESS - Multi-block write has been queued
+ * SDCARD_OPERATION_BUSY - The card is already busy and cannot accept your write
+ * SDCARD_OPERATION_FAILURE - A fatal error occured, card will be reset
+ */
+sdcardOperationStatus_e sdcard_beginWriteBlocks(uint32_t blockIndex, uint32_t blockCount)
+{
+ if (sdcard.state != SDCARD_STATE_READY) {
+ if (sdcard.state == SDCARD_STATE_WRITING_MULTIPLE_BLOCKS) {
+ if (blockIndex == sdcard.multiWriteNextBlock) {
+ // Assume that the caller wants to continue the multi-block write they already have in progress!
+ return SDCARD_OPERATION_SUCCESS;
+ } else if (sdcard_endWriteBlocks() != SDCARD_OPERATION_SUCCESS) {
+ return SDCARD_OPERATION_BUSY;
+ } // Else we've completed the previous multi-block write and can fall through to start the new one
+ } else {
+ return SDCARD_OPERATION_BUSY;
+ }
+ }
+
+ sdcard_select();
+
+ if (
+ sdcard_sendAppCommand(SDCARD_ACOMMAND_SET_WR_BLOCK_ERASE_COUNT, blockCount) == 0
+ && sdcard_sendCommand(SDCARD_COMMAND_WRITE_MULTIPLE_BLOCK, sdcard.highCapacity ? blockIndex : blockIndex * SDCARD_BLOCK_SIZE) == 0
+ ) {
+ sdcard.state = SDCARD_STATE_WRITING_MULTIPLE_BLOCKS;
+ sdcard.multiWriteBlocksRemain = blockCount;
+ sdcard.multiWriteNextBlock = blockIndex;
+
+ // Leave the card selected
+ return SDCARD_OPERATION_SUCCESS;
+ } else {
+ sdcard_deselect();
+
+ sdcard_reset();
+
+ return SDCARD_OPERATION_FAILURE;
+ }
+}
+
+/**
+ * Read the 512-byte block with the given index into the given 512-byte buffer.
+ *
+ * When the read completes, your callback will be called. If the read was successful, the buffer pointer will be the
+ * same buffer you originally passed in, otherwise the buffer will be set to NULL.
+ *
+ * You must keep the pointer to the buffer valid until the operation completes!
+ *
+ * Returns:
+ * true - The operation was successfully queued for later completion, your callback will be called later
+ * false - The operation could not be started due to the card being busy (try again later).
+ */
+bool sdcard_readBlock(uint32_t blockIndex, uint8_t *buffer, sdcard_operationCompleteCallback_c callback, uint32_t callbackData)
+{
+ if (sdcard.state != SDCARD_STATE_READY) {
+ if (sdcard.state == SDCARD_STATE_WRITING_MULTIPLE_BLOCKS) {
+ if (sdcard_endWriteBlocks() != SDCARD_OPERATION_SUCCESS) {
+ return false;
+ }
+ } else {
+ return false;
+ }
+ }
+
+#ifdef SDCARD_PROFILING
+ sdcard.pendingOperation.profileStartTime = micros();
+#endif
+
+ sdcard_select();
+
+ // Standard size cards use byte addressing, high capacity cards use block addressing
+ uint8_t status = sdcard_sendCommand(SDCARD_COMMAND_READ_SINGLE_BLOCK, sdcard.highCapacity ? blockIndex : blockIndex * SDCARD_BLOCK_SIZE);
+
+ if (status == 0) {
+ sdcard.pendingOperation.buffer = buffer;
+ sdcard.pendingOperation.blockIndex = blockIndex;
+ sdcard.pendingOperation.callback = callback;
+ sdcard.pendingOperation.callbackData = callbackData;
+
+ sdcard.state = SDCARD_STATE_READING;
+
+ sdcard.operationStartTime = millis();
+
+ // Leave the card selected for the whole transaction
+
+ return true;
+ } else {
+ sdcard_deselect();
+
+ return false;
+ }
+}
+
+/**
+ * Returns true if the SD card has successfully completed its startup procedures.
+ */
+bool sdcard_isInitialized(void)
+{
+ return sdcard.state >= SDCARD_STATE_READY;
+}
+
+const sdcardMetadata_t* sdcard_getMetadata(void)
+{
+ return &sdcard.metadata;
+}
+
+#ifdef SDCARD_PROFILING
+
+void sdcard_setProfilerCallback(sdcard_profilerCallback_c callback)
+{
+ sdcard.profiler = callback;
+}
+
+#endif
+
+#endif
diff --git a/src/main/drivers/sdio_f4xx.c b/src/main/drivers/sdio_f4xx.c
index c42141a13e..3a8653cdbf 100644
--- a/src/main/drivers/sdio_f4xx.c
+++ b/src/main/drivers/sdio_f4xx.c
@@ -31,9 +31,11 @@
#include "stdbool.h"
#include
-#include "sdmmc_sdio.h"
-
#include "platform.h"
+
+#ifdef USE_SDCARD_SDIO
+
+#include "sdmmc_sdio.h"
#include "stm32f4xx_gpio.h"
#include "pg/pg.h"
@@ -1899,3 +1901,4 @@ void SDIO_DMA_ST6_IRQHandler(dmaChannelDescriptor_t *dma)
}
/* ------------------------------------------------------------------------------------------------------------------*/
+#endif
diff --git a/src/main/drivers/sdio_f7xx.c b/src/main/drivers/sdio_f7xx.c
index 7b9984a005..e33906c618 100644
--- a/src/main/drivers/sdio_f7xx.c
+++ b/src/main/drivers/sdio_f7xx.c
@@ -28,9 +28,11 @@
#include "stdbool.h"
#include
-#include "sdmmc_sdio.h"
-
#include "platform.h"
+
+#ifdef USE_SDCARD_SDIO
+
+#include "sdmmc_sdio.h"
#include "stm32f7xx.h"
#include "drivers/io.h"
@@ -1899,3 +1901,4 @@ void SDMMC_DMA_ST6_IRQHandler(dmaChannelDescriptor_t *dma)
}
/* ------------------------------------------------------------------------------------------------------------------*/
+#endif
diff --git a/src/main/interface/cli.c b/src/main/interface/cli.c
index e0233dc98c..337ee64e4c 100644
--- a/src/main/interface/cli.c
+++ b/src/main/interface/cli.c
@@ -3816,7 +3816,7 @@ const cliResourceValue_t resourceTable[] = {
DEFS( OWNER_COMPASS_EXTI, PG_COMPASS_CONFIG, compassConfig_t, interruptTag ),
#endif
#endif
-#ifdef USE_SDCARD
+#ifdef USE_SDCARD_SPI
DEFS( OWNER_SDCARD_CS, PG_SDCARD_CONFIG, sdcardConfig_t, chipSelectTag ),
DEFS( OWNER_SDCARD_DETECT, PG_SDCARD_CONFIG, sdcardConfig_t, cardDetectTag ),
#endif
diff --git a/src/main/interface/settings.c b/src/main/interface/settings.c
index 27a000cfc0..42282bb815 100644
--- a/src/main/interface/settings.c
+++ b/src/main/interface/settings.c
@@ -393,6 +393,12 @@ static const char * const lookupTableVtxLowPowerDisarm[] = {
};
#endif
+#ifdef USE_SDCARD
+static const char * const lookupTableSdcardMode[] = {
+ "OFF", "SPI", "SDIO"
+};
+#endif
+
#define LOOKUP_TABLE_ENTRY(name) { name, ARRAYLEN(name) }
const lookupTableEntry_t lookupTables[] = {
@@ -490,6 +496,9 @@ const lookupTableEntry_t lookupTables[] = {
LOOKUP_TABLE_ENTRY(lookupTableVtxLowPowerDisarm),
#endif
LOOKUP_TABLE_ENTRY(lookupTableGyroHardware),
+#ifdef USE_SDCARD
+ LOOKUP_TABLE_ENTRY(lookupTableSdcardMode),
+#endif
};
#undef LOOKUP_TABLE_ENTRY
@@ -933,7 +942,12 @@ const clivalue_t valueTable[] = {
// PG_SDCARD_CONFIG
#ifdef USE_SDCARD
+ { "sdcard_detect_inverted", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SDCARD_CONFIG, offsetof(sdcardConfig_t, cardDetectInverted) },
+ { "sdcard_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SDCARD_MODE }, PG_SDCARD_CONFIG, offsetof(sdcardConfig_t, mode) },
+#endif
+#ifdef USE_SDCARD_SPI
{ "sdcard_dma", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SDCARD_CONFIG, offsetof(sdcardConfig_t, useDma) },
+ { "sdcard_spi_bus", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, SPIDEV_COUNT }, PG_SDCARD_CONFIG, offsetof(sdcardConfig_t, device) },
#endif
#ifdef USE_SDCARD_SDIO
{ "sdio_clk_bypass", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SDIO_CONFIG, offsetof(sdioConfig_t, clockBypass) },
diff --git a/src/main/interface/settings.h b/src/main/interface/settings.h
index f159bec67e..a42ed5bc76 100644
--- a/src/main/interface/settings.h
+++ b/src/main/interface/settings.h
@@ -120,6 +120,9 @@ typedef enum {
TABLE_VTX_LOW_POWER_DISARM,
#endif
TABLE_GYRO_HARDWARE,
+#ifdef USE_SDCARD
+ TABLE_SDCARD_MODE,
+#endif
LOOKUP_TABLE_COUNT
} lookupTableIndex_e;
diff --git a/src/main/pg/sdcard.c b/src/main/pg/sdcard.c
index 07d5d7d291..74e8022c4d 100644
--- a/src/main/pg/sdcard.c
+++ b/src/main/pg/sdcard.c
@@ -38,32 +38,32 @@ PG_REGISTER_WITH_RESET_FN(sdcardConfig_t, sdcardConfig, PG_SDCARD_CONFIG, 0);
void pgResetFn_sdcardConfig(sdcardConfig_t *config)
{
config->useDma = false;
-#ifdef SDCARD_SPI_INSTANCE
- config->enabled = 1;
- config->device = spiDeviceByInstance(SDCARD_SPI_INSTANCE);
-#elif defined(USE_SDCARD_SDIO)
- config->enabled = 1;
-#else
config->enabled = 0;
- config->device = 0;
-#endif
-#ifdef SDCARD_DETECT_PIN
- config->cardDetectTag = IO_TAG(SDCARD_DETECT_PIN);
-#else
- config->cardDetectTag = IO_TAG_NONE;
-#endif
-#ifdef SDCARD_SPI_CS_PIN
- config->chipSelectTag = IO_TAG(SDCARD_SPI_CS_PIN);
-#else
- config->chipSelectTag = IO_TAG_NONE;
+ config->device = SPI_DEV_TO_CFG(SPIINVALID);
+ config->mode = SDCARD_MODE_NONE;
+
+ // We can safely handle SPI and SDIO cases separately on custom targets, as these are exclusive per target.
+ // On generic targets, SPI has precedence over SDIO; SDIO must be post-flash configured.
+
+#ifdef USE_SDCARD_SDIO
+ config->mode = SDCARD_MODE_SDIO;
+ config->enabled = 1;
#endif
-#ifdef SDCARD_DETECT_INVERTED
- config->cardDetectInverted = 1;
-#else
- config->cardDetectInverted = 0;
+#ifdef USE_SDCARD_SPI
+ SPIDevice spidevice = spiDeviceByInstance(SDCARD_SPI_INSTANCE);
+ config->device = SPI_DEV_TO_CFG(spidevice);
+ config->chipSelectTag = IO_TAG(SDCARD_SPI_CS_PIN);
+
+ if (spidevice != SPIINVALID && config->chipSelectTag) {
+ config->enabled = 1;
+ config->mode = SDCARD_MODE_SPI;
+ }
#endif
+ config->cardDetectTag = IO_TAG(SDCARD_DETECT_PIN);
+ config->cardDetectInverted = SDCARD_DETECT_IS_INVERTED;
+
#if defined(SDCARD_DMA_STREAM_TX_FULL)
config->dmaIdentifier = (uint8_t)dmaGetIdentifier(SDCARD_DMA_STREAM_TX_FULL);
#elif defined(SDCARD_DMA_CHANNEL_TX)
diff --git a/src/main/pg/sdcard.h b/src/main/pg/sdcard.h
index 338d03c41d..042dd5f0bb 100644
--- a/src/main/pg/sdcard.h
+++ b/src/main/pg/sdcard.h
@@ -23,15 +23,22 @@
#include "pg/pg.h"
#include "drivers/io.h"
+typedef enum {
+ SDCARD_MODE_NONE = 0,
+ SDCARD_MODE_SPI,
+ SDCARD_MODE_SDIO
+} sdcardMode_e;
+
typedef struct sdcardConfig_s {
uint8_t useDma;
uint8_t enabled;
- uint8_t device;
+ int8_t device;
ioTag_t cardDetectTag;
ioTag_t chipSelectTag;
uint8_t cardDetectInverted;
uint8_t dmaIdentifier;
uint8_t dmaChannel;
+ sdcardMode_e mode;
} sdcardConfig_t;
PG_DECLARE(sdcardConfig_t, sdcardConfig);
diff --git a/src/main/target/ALIENFLIGHTF4/target.h b/src/main/target/ALIENFLIGHTF4/target.h
index f4aa585985..19a3845370 100644
--- a/src/main/target/ALIENFLIGHTF4/target.h
+++ b/src/main/target/ALIENFLIGHTF4/target.h
@@ -68,6 +68,7 @@
#define USE_BARO_BMP280
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB11
#define SDCARD_SPI_INSTANCE SPI2
diff --git a/src/main/target/ALIENFLIGHTF4/target.mk b/src/main/target/ALIENFLIGHTF4/target.mk
index e7acd65ab9..9aa170bb0a 100644
--- a/src/main/target/ALIENFLIGHTF4/target.mk
+++ b/src/main/target/ALIENFLIGHTF4/target.mk
@@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
-FEATURES += SDCARD VCP ONBOARDFLASH
+FEATURES += SDCARD_SPI VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \
diff --git a/src/main/target/ALIENFLIGHTNGF7/target.h b/src/main/target/ALIENFLIGHTNGF7/target.h
index 95e75b2535..eb0fa8090b 100644
--- a/src/main/target/ALIENFLIGHTNGF7/target.h
+++ b/src/main/target/ALIENFLIGHTNGF7/target.h
@@ -82,6 +82,7 @@
#define BMP280_SPI_INSTANCE SPI3
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB11
#define SDCARD_SPI_INSTANCE SPI2
diff --git a/src/main/target/ALIENFLIGHTNGF7/target.mk b/src/main/target/ALIENFLIGHTNGF7/target.mk
index 2b63a22591..fa6f397b66 100644
--- a/src/main/target/ALIENFLIGHTNGF7/target.mk
+++ b/src/main/target/ALIENFLIGHTNGF7/target.mk
@@ -1,5 +1,5 @@
F7X2RE_TARGETS += $(TARGET)
-FEATURES += SDCARD VCP ONBOARDFLASH
+FEATURES += SDCARD_SPI VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \
diff --git a/src/main/target/ANYFCF7/target.h b/src/main/target/ANYFCF7/target.h
index 9c3fe9085b..06b9020934 100644
--- a/src/main/target/ANYFCF7/target.h
+++ b/src/main/target/ANYFCF7/target.h
@@ -135,6 +135,7 @@
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PD3
#define SDCARD_SPI_INSTANCE SPI4
diff --git a/src/main/target/ANYFCF7/target.mk b/src/main/target/ANYFCF7/target.mk
index 1145bf5015..25b9d7a30d 100644
--- a/src/main/target/ANYFCF7/target.mk
+++ b/src/main/target/ANYFCF7/target.mk
@@ -1,5 +1,5 @@
F7X5XG_TARGETS += $(TARGET)
-FEATURES += SDCARD VCP
+FEATURES += SDCARD_SPI VCP
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \
diff --git a/src/main/target/BEEROTORF4/target.h b/src/main/target/BEEROTORF4/target.h
index 3957013a50..297db18a2e 100644
--- a/src/main/target/BEEROTORF4/target.h
+++ b/src/main/target/BEEROTORF4/target.h
@@ -62,6 +62,7 @@
#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_ST0_HANDLER
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_PIN PC3
#define SDCARD_DETECT_INVERTED
#define SDCARD_SPI_INSTANCE SPI2
diff --git a/src/main/target/BEEROTORF4/target.mk b/src/main/target/BEEROTORF4/target.mk
index a54056c083..6b6cef764e 100644
--- a/src/main/target/BEEROTORF4/target.mk
+++ b/src/main/target/BEEROTORF4/target.mk
@@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
-FEATURES += VCP SDCARD
+FEATURES += VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_spi_icm20689.c \
diff --git a/src/main/target/BETAFLIGHTF3/target.h b/src/main/target/BETAFLIGHTF3/target.h
index f0092f1a50..956b93d182 100644
--- a/src/main/target/BETAFLIGHTF3/target.h
+++ b/src/main/target/BETAFLIGHTF3/target.h
@@ -120,6 +120,7 @@
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2
diff --git a/src/main/target/BETAFLIGHTF3/target.mk b/src/main/target/BETAFLIGHTF3/target.mk
index 297f9be3f1..d470b1b5e3 100644
--- a/src/main/target/BETAFLIGHTF3/target.mk
+++ b/src/main/target/BETAFLIGHTF3/target.mk
@@ -1,6 +1,6 @@
F3_TARGETS += $(TARGET)
-FEATURES = VCP SDCARD
+FEATURES = VCP SDCARD_SPI
TARGET_FLAGS = -DSPRACINGF3
TARGET_SRC = \
diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h
index 6192fd8bf9..e35384a72c 100644
--- a/src/main/target/BLUEJAYF4/target.h
+++ b/src/main/target/BLUEJAYF4/target.h
@@ -73,6 +73,7 @@
#define MS5611_I2C_INSTANCE I2CDEV_1
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PD2
#define SDCARD_SPI_INSTANCE SPI3
diff --git a/src/main/target/BLUEJAYF4/target.mk b/src/main/target/BLUEJAYF4/target.mk
index 9607e3fcf9..bbde2b8087 100644
--- a/src/main/target/BLUEJAYF4/target.mk
+++ b/src/main/target/BLUEJAYF4/target.mk
@@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
-FEATURES += SDCARD VCP ONBOARDFLASH
+FEATURES += SDCARD_SPI VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6500.c \
diff --git a/src/main/target/CHEBUZZF3/target.h b/src/main/target/CHEBUZZF3/target.h
index 6ca5e1fd11..fc0b003195 100644
--- a/src/main/target/CHEBUZZF3/target.h
+++ b/src/main/target/CHEBUZZF3/target.h
@@ -46,6 +46,7 @@
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
diff --git a/src/main/target/CHEBUZZF3/target.mk b/src/main/target/CHEBUZZF3/target.mk
index 2ece8cd60a..11eca6ef24 100644
--- a/src/main/target/CHEBUZZF3/target.mk
+++ b/src/main/target/CHEBUZZF3/target.mk
@@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
-FEATURES = VCP SDCARD
+FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/compass/compass_hmc5883l.c \
diff --git a/src/main/target/CLRACINGF4/target.h b/src/main/target/CLRACINGF4/target.h
index f82e507fdf..d101162a12 100644
--- a/src/main/target/CLRACINGF4/target.h
+++ b/src/main/target/CLRACINGF4/target.h
@@ -70,6 +70,7 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_PIN PB7
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
diff --git a/src/main/target/CLRACINGF4/target.mk b/src/main/target/CLRACINGF4/target.mk
index a2703931df..c3c53e1ab5 100644
--- a/src/main/target/CLRACINGF4/target.mk
+++ b/src/main/target/CLRACINGF4/target.mk
@@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
-FEATURES = VCP SDCARD ONBOARDFLASH
+FEATURES = VCP SDCARD_SPI ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_mpu6500.c \
diff --git a/src/main/target/CLRACINGF7/target.h b/src/main/target/CLRACINGF7/target.h
index df72cfc95e..cf2e3517bb 100644
--- a/src/main/target/CLRACINGF7/target.h
+++ b/src/main/target/CLRACINGF7/target.h
@@ -65,6 +65,7 @@
//define use SD card
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_PIN PA8
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
diff --git a/src/main/target/CLRACINGF7/target.mk b/src/main/target/CLRACINGF7/target.mk
index 2f2f023cd6..7073804f28 100644
--- a/src/main/target/CLRACINGF7/target.mk
+++ b/src/main/target/CLRACINGF7/target.mk
@@ -1,5 +1,5 @@
F7X2RE_TARGETS += $(TARGET)
-FEATURES += VCP ONBOARDFLASH SDCARD
+FEATURES += VCP ONBOARDFLASH SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_mpu6500.c \
diff --git a/src/main/target/F4BY/target.h b/src/main/target/F4BY/target.h
index 2380b83f84..d1ddd3f631 100644
--- a/src/main/target/F4BY/target.h
+++ b/src/main/target/F4BY/target.h
@@ -61,6 +61,7 @@
#define USE_BARO_MS5611
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN PE15
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream3
diff --git a/src/main/target/F4BY/target.mk b/src/main/target/F4BY/target.mk
index 5fa6a06704..50e30b86ed 100644
--- a/src/main/target/F4BY/target.mk
+++ b/src/main/target/F4BY/target.mk
@@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
-FEATURES += SDCARD VCP
+FEATURES += SDCARD_SPI VCP
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \
diff --git a/src/main/target/FISHDRONEF4/target.h b/src/main/target/FISHDRONEF4/target.h
index 9e408f62e7..13a94fe5cf 100644
--- a/src/main/target/FISHDRONEF4/target.h
+++ b/src/main/target/FISHDRONEF4/target.h
@@ -106,6 +106,7 @@
// *************** SDCARD *****************************
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB7
#define SDCARD_SPI_INSTANCE SPI3
diff --git a/src/main/target/FISHDRONEF4/target.mk b/src/main/target/FISHDRONEF4/target.mk
index 48b834c6e4..a40318066f 100644
--- a/src/main/target/FISHDRONEF4/target.mk
+++ b/src/main/target/FISHDRONEF4/target.mk
@@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
-FEATURES += SDCARD VCP ONBOARDFLASH
+FEATURES += SDCARD_SPI VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6500.c \
diff --git a/src/main/target/FRSKYF3/target.h b/src/main/target/FRSKYF3/target.h
index 8d39df2dae..7f07389c7a 100644
--- a/src/main/target/FRSKYF3/target.h
+++ b/src/main/target/FRSKYF3/target.h
@@ -127,6 +127,7 @@
#define SPI1_MOSI_PIN PA7
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB5
#define SDCARD_SPI_INSTANCE SPI1
diff --git a/src/main/target/FRSKYF3/target.mk b/src/main/target/FRSKYF3/target.mk
index 1a9b96b664..395c6cf1c9 100644
--- a/src/main/target/FRSKYF3/target.mk
+++ b/src/main/target/FRSKYF3/target.mk
@@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
-FEATURES = VCP SDCARD
+FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
diff --git a/src/main/target/FRSKYF4/target.h b/src/main/target/FRSKYF4/target.h
index 1d5716f880..4cbd0529f7 100644
--- a/src/main/target/FRSKYF4/target.h
+++ b/src/main/target/FRSKYF4/target.h
@@ -63,6 +63,7 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB7
#define SDCARD_SPI_INSTANCE SPI2
diff --git a/src/main/target/FRSKYF4/target.mk b/src/main/target/FRSKYF4/target.mk
index 5a9f7aea5b..85bd85add3 100644
--- a/src/main/target/FRSKYF4/target.mk
+++ b/src/main/target/FRSKYF4/target.mk
@@ -1,6 +1,6 @@
F405_TARGETS += $(TARGET)
-FEATURES = VCP SDCARD
+FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \
diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h
index a816cd810b..4fbc5a0ede 100644
--- a/src/main/target/FURYF3/target.h
+++ b/src/main/target/FURYF3/target.h
@@ -116,6 +116,7 @@
#else
#define USE_SDCARD
+ #define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB2
#define SDCARD_SPI_INSTANCE SPI2
diff --git a/src/main/target/FURYF3/target.mk b/src/main/target/FURYF3/target.mk
index 37ef421bb0..be5e24d82f 100644
--- a/src/main/target/FURYF3/target.mk
+++ b/src/main/target/FURYF3/target.mk
@@ -2,7 +2,7 @@ F3_TARGETS += $(TARGET)
ifeq ($(TARGET), FURYF3OSD)
FEATURES += VCP ONBOARDFLASH
else
-FEATURES += VCP SDCARD
+FEATURES += VCP SDCARD_SPI
endif
TARGET_SRC = \
diff --git a/src/main/target/FURYF4/target.h b/src/main/target/FURYF4/target.h
index 736ffab4b2..a534185ef0 100644
--- a/src/main/target/FURYF4/target.h
+++ b/src/main/target/FURYF4/target.h
@@ -76,6 +76,7 @@
#define MS5611_I2C_INSTANCE I2CDEV_1
#define USE_SDCARD
+ #define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PD2
#define SDCARD_SPI_INSTANCE SPI2
diff --git a/src/main/target/FURYF4/target.mk b/src/main/target/FURYF4/target.mk
index 06b60c1c7f..707a725aa7 100644
--- a/src/main/target/FURYF4/target.mk
+++ b/src/main/target/FURYF4/target.mk
@@ -2,7 +2,7 @@ F405_TARGETS += $(TARGET)
ifeq ($(TARGET), FURYF4OSD)
FEATURES += VCP ONBOARDFLASH
else
-FEATURES += VCP ONBOARDFLASH SDCARD
+FEATURES += VCP ONBOARDFLASH SDCARD_SPI
endif
TARGET_SRC = \
diff --git a/src/main/target/FURYF7/target.h b/src/main/target/FURYF7/target.h
index c141890265..896f1f1fa5 100644
--- a/src/main/target/FURYF7/target.h
+++ b/src/main/target/FURYF7/target.h
@@ -78,6 +78,7 @@
#define SPI4_MOSI_PIN PE14
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PD2
#define SDCARD_SPI_INSTANCE SPI4
diff --git a/src/main/target/FURYF7/target.mk b/src/main/target/FURYF7/target.mk
index 003875026a..bc543450ca 100644
--- a/src/main/target/FURYF7/target.mk
+++ b/src/main/target/FURYF7/target.mk
@@ -1,5 +1,5 @@
F7X5XG_TARGETS += $(TARGET)
-FEATURES += SDCARD VCP ONBOARDFLASH
+FEATURES += SDCARD_SPI VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_spi_icm20689.c
diff --git a/src/main/target/HAKRCF722/target.mk b/src/main/target/HAKRCF722/target.mk
old mode 100755
new mode 100644
diff --git a/src/main/target/KAKUTEF4/FLYWOOF405.mk b/src/main/target/KAKUTEF4/FLYWOOF405.mk
old mode 100755
new mode 100644
diff --git a/src/main/target/KAKUTEF7/target.h b/src/main/target/KAKUTEF7/target.h
index 3bbb2bdd8c..93819a5c64 100644
--- a/src/main/target/KAKUTEF7/target.h
+++ b/src/main/target/KAKUTEF7/target.h
@@ -123,6 +123,7 @@
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PD8
#define SDCARD_SPI_INSTANCE SPI1
diff --git a/src/main/target/KAKUTEF7/target.mk b/src/main/target/KAKUTEF7/target.mk
index 1bf2b5a0e6..1c53e1e72e 100644
--- a/src/main/target/KAKUTEF7/target.mk
+++ b/src/main/target/KAKUTEF7/target.mk
@@ -4,7 +4,7 @@ else
F7X5XG_TARGETS += $(TARGET)
endif
-FEATURES += SDCARD VCP
+FEATURES += SDCARD_SPI VCP
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
diff --git a/src/main/target/KIWIF4/target.h b/src/main/target/KIWIF4/target.h
index b5ff5ed0e2..b80ac659f7 100644
--- a/src/main/target/KIWIF4/target.h
+++ b/src/main/target/KIWIF4/target.h
@@ -81,6 +81,7 @@
#if defined(KIWIF4V2)
#define USE_SDCARD
+#define USE_SDCARD_SPI
//#define SDCARD_DETECT_PIN PB9
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN PB12
diff --git a/src/main/target/KIWIF4/target.mk b/src/main/target/KIWIF4/target.mk
index 1cb2eec9a1..0fb93c0b75 100644
--- a/src/main/target/KIWIF4/target.mk
+++ b/src/main/target/KIWIF4/target.mk
@@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
-FEATURES += VCP ONBOARDFLASH SDCARD
+FEATURES += VCP ONBOARDFLASH SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \
diff --git a/src/main/target/KROOZX/target.h b/src/main/target/KROOZX/target.h
index cb8d11219b..6918966a70 100644
--- a/src/main/target/KROOZX/target.h
+++ b/src/main/target/KROOZX/target.h
@@ -66,6 +66,7 @@
#define USE_BARO_MS5611
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC13
#define SDCARD_SPI_INSTANCE SPI3
diff --git a/src/main/target/KROOZX/target.mk b/src/main/target/KROOZX/target.mk
index 0c294619c1..e12a6ce00f 100644
--- a/src/main/target/KROOZX/target.mk
+++ b/src/main/target/KROOZX/target.mk
@@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
-FEATURES += VCP SDCARD
+FEATURES += VCP SDCARD_SPI
HSE_VALUE = 16000000
TARGET_SRC = \
diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h
index 8b3ba5138d..affc907e6b 100644
--- a/src/main/target/LUX_RACE/target.h
+++ b/src/main/target/LUX_RACE/target.h
@@ -77,6 +77,7 @@
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC13
#define SDCARD_SPI_INSTANCE SPI2
diff --git a/src/main/target/LUX_RACE/target.mk b/src/main/target/LUX_RACE/target.mk
index a85188a428..f5d310faab 100644
--- a/src/main/target/LUX_RACE/target.mk
+++ b/src/main/target/LUX_RACE/target.mk
@@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
-FEATURES = VCP SDCARD
+FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
diff --git a/src/main/target/MATEKF405/target.h b/src/main/target/MATEKF405/target.h
index 0f9c71e7f7..60e2e58d81 100644
--- a/src/main/target/MATEKF405/target.h
+++ b/src/main/target/MATEKF405/target.h
@@ -104,6 +104,7 @@
// *************** SD Card **************************
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define SDCARD_SPI_INSTANCE SPI3
#define SDCARD_SPI_CS_PIN PC1
diff --git a/src/main/target/MATEKF405/target.mk b/src/main/target/MATEKF405/target.mk
index 2504bf72d5..d43148dd65 100644
--- a/src/main/target/MATEKF405/target.mk
+++ b/src/main/target/MATEKF405/target.mk
@@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
-FEATURES += VCP ONBOARDFLASH SDCARD
+FEATURES += VCP ONBOARDFLASH SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6500.c \
diff --git a/src/main/target/MATEKF411/target.mk b/src/main/target/MATEKF411/target.mk
index 548aef1968..cb6bf78f82 100644
--- a/src/main/target/MATEKF411/target.mk
+++ b/src/main/target/MATEKF411/target.mk
@@ -1,5 +1,5 @@
F411_TARGETS += $(TARGET)
-FEATURES += SDCARD VCP
+FEATURES += SDCARD_SPI VCP
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6500.c \
diff --git a/src/main/target/MATEKF411RX/target.mk b/src/main/target/MATEKF411RX/target.mk
index 977b93bf5a..91e00b6b81 100644
--- a/src/main/target/MATEKF411RX/target.mk
+++ b/src/main/target/MATEKF411RX/target.mk
@@ -1,6 +1,6 @@
F411_TARGETS += $(TARGET)
-FEATURES += VCP SDCARD
+FEATURES += VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \
diff --git a/src/main/target/MATEKF722/target.h b/src/main/target/MATEKF722/target.h
index a7a9aff63e..030716328b 100644
--- a/src/main/target/MATEKF722/target.h
+++ b/src/main/target/MATEKF722/target.h
@@ -86,6 +86,7 @@
// *************** SD Card **************************
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define USE_SPI_DEVICE_3
diff --git a/src/main/target/MATEKF722/target.mk b/src/main/target/MATEKF722/target.mk
index 32f47a0c40..5926db3bab 100644
--- a/src/main/target/MATEKF722/target.mk
+++ b/src/main/target/MATEKF722/target.mk
@@ -1,5 +1,5 @@
F7X2RE_TARGETS += $(TARGET)
-FEATURES += SDCARD VCP
+FEATURES += SDCARD_SPI VCP
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6500.c \
diff --git a/src/main/target/MIDELICF3/target.h b/src/main/target/MIDELICF3/target.h
index 8ecf651940..ee396595ec 100644
--- a/src/main/target/MIDELICF3/target.h
+++ b/src/main/target/MIDELICF3/target.h
@@ -82,9 +82,10 @@
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
-#define SDCARD_SPI_INSTANCE SPI2
-#define SDCARD_SPI_CS_PIN PB12
-#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
+#define USE_SDCARD_SPI
+#define SDCARD_SPI_INSTANCE SPI2
+#define SDCARD_SPI_CS_PIN PB12
+#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
#define USE_ADC
#define ADC_INSTANCE ADC1
diff --git a/src/main/target/MIDELICF3/target.mk b/src/main/target/MIDELICF3/target.mk
index 0c78eda412..a6a7ec24a2 100644
--- a/src/main/target/MIDELICF3/target.mk
+++ b/src/main/target/MIDELICF3/target.mk
@@ -1,6 +1,6 @@
F3_TARGETS += $(TARGET)
-FEATURES = VCP SDCARD
+FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
diff --git a/src/main/target/MOTOLABF4/target.h b/src/main/target/MOTOLABF4/target.h
index 6579923dc4..1522e18010 100644
--- a/src/main/target/MOTOLABF4/target.h
+++ b/src/main/target/MOTOLABF4/target.h
@@ -116,6 +116,7 @@
#define USE_SPI_DEVICE_2 // SDcard
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC13
#define SDCARD_SPI_INSTANCE SPI2
diff --git a/src/main/target/MOTOLABF4/target.mk b/src/main/target/MOTOLABF4/target.mk
index 8f348d0afb..75ca759a56 100644
--- a/src/main/target/MOTOLABF4/target.mk
+++ b/src/main/target/MOTOLABF4/target.mk
@@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
-FEATURES += SDCARD VCP
+FEATURES += SDCARD_SPI VCP
ifeq ($(TARGET), MLTEMPF4)
TARGET_SRC = \
diff --git a/src/main/target/NERO/target.h b/src/main/target/NERO/target.h
index e4c00ce619..fa24527747 100644
--- a/src/main/target/NERO/target.h
+++ b/src/main/target/NERO/target.h
@@ -54,6 +54,7 @@
#define GYRO_1_ALIGN CW0_DEG
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PD2
#define SDCARD_SPI_INSTANCE SPI3
diff --git a/src/main/target/NERO/target.mk b/src/main/target/NERO/target.mk
index e2e1a265d5..3a5c6c7bf3 100644
--- a/src/main/target/NERO/target.mk
+++ b/src/main/target/NERO/target.mk
@@ -1,5 +1,5 @@
F7X2RE_TARGETS += $(TARGET)
-FEATURES += SDCARD VCP
+FEATURES += SDCARD_SPI VCP
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6500.c \
diff --git a/src/main/target/NUCLEOF7/target.h b/src/main/target/NUCLEOF7/target.h
index 5730790df6..cf8714bd86 100644
--- a/src/main/target/NUCLEOF7/target.h
+++ b/src/main/target/NUCLEOF7/target.h
@@ -124,6 +124,7 @@
#define SPI4_MOSI_PIN PE14
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PF14
#define SDCARD_SPI_INSTANCE SPI4
diff --git a/src/main/target/NUCLEOF7/target.mk b/src/main/target/NUCLEOF7/target.mk
index f0ab8b3cb2..bc21e51f75 100644
--- a/src/main/target/NUCLEOF7/target.mk
+++ b/src/main/target/NUCLEOF7/target.mk
@@ -1,5 +1,5 @@
F7X6XG_TARGETS += $(TARGET)
-FEATURES += SDCARD VCP
+FEATURES += SDCARD_SPI VCP
TARGET_SRC = \
drivers/accgyro/accgyro_fake.c \
diff --git a/src/main/target/NUCLEOF722/target.mk b/src/main/target/NUCLEOF722/target.mk
index 6b9563c661..9beac9f7c9 100644
--- a/src/main/target/NUCLEOF722/target.mk
+++ b/src/main/target/NUCLEOF722/target.mk
@@ -1,5 +1,5 @@
F7X2RE_TARGETS += $(TARGET)
-FEATURES += VCP SDIO
+FEATURES += VCP SDCARD_SDIO
TARGET_SRC = \
drivers/accgyro/accgyro_fake.c \
diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h
index 2aa250b620..c73bbda271 100644
--- a/src/main/target/OMNIBUS/target.h
+++ b/src/main/target/OMNIBUS/target.h
@@ -142,6 +142,7 @@
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2
diff --git a/src/main/target/OMNIBUS/target.mk b/src/main/target/OMNIBUS/target.mk
index 68a4060c79..109f4a4c71 100644
--- a/src/main/target/OMNIBUS/target.mk
+++ b/src/main/target/OMNIBUS/target.mk
@@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
-FEATURES = VCP SDCARD
+FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
diff --git a/src/main/target/OMNIBUSF4/EXUAVF4PRO.mk b/src/main/target/OMNIBUSF4/EXUAVF4PRO.mk
index 592a073315..a168c034b9 100644
--- a/src/main/target/OMNIBUSF4/EXUAVF4PRO.mk
+++ b/src/main/target/OMNIBUSF4/EXUAVF4PRO.mk
@@ -1,2 +1,2 @@
#EXUAVF4PRO
-FEATURES = VCP SDCARD
\ No newline at end of file
+FEATURES = VCP SDCARD_SPI
\ No newline at end of file
diff --git a/src/main/target/OMNIBUSF4/OMNIBUSF4SD.mk b/src/main/target/OMNIBUSF4/OMNIBUSF4SD.mk
index 2f6492da96..58c0f73f15 100644
--- a/src/main/target/OMNIBUSF4/OMNIBUSF4SD.mk
+++ b/src/main/target/OMNIBUSF4/OMNIBUSF4SD.mk
@@ -1,2 +1,2 @@
# the OMNIBUSF4SD has an SDCARD instead of flash, a BMP280 baro and therefore a slightly different ppm/pwm and SPI mapping
-FEATURES = VCP SDCARD
+FEATURES = VCP SDCARD_SPI
diff --git a/src/main/target/OMNIBUSF4/target.h b/src/main/target/OMNIBUSF4/target.h
index a0caea9952..f39a31a834 100644
--- a/src/main/target/OMNIBUSF4/target.h
+++ b/src/main/target/OMNIBUSF4/target.h
@@ -152,6 +152,7 @@
#if defined(OMNIBUSF4SD)
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB7
#define SDCARD_SPI_INSTANCE SPI2
diff --git a/src/main/target/OMNIBUSF7/target.h b/src/main/target/OMNIBUSF7/target.h
index fa6a9a415c..d31d73f003 100644
--- a/src/main/target/OMNIBUSF7/target.h
+++ b/src/main/target/OMNIBUSF7/target.h
@@ -184,6 +184,7 @@
//SD-----------------------------------------
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PE3
#define SDCARD_SPI_INSTANCE SPI4
diff --git a/src/main/target/OMNIBUSF7/target.mk b/src/main/target/OMNIBUSF7/target.mk
index 0fdbdcdfe1..5285a9379f 100644
--- a/src/main/target/OMNIBUSF7/target.mk
+++ b/src/main/target/OMNIBUSF7/target.mk
@@ -2,7 +2,7 @@ F7X5XG_TARGETS += $(TARGET)
ifeq ($(TARGET), FPVM_BETAFLIGHTF7)
FEATURES = VCP ONBOARDFLASH
else
-FEATURES = VCP SDCARD
+FEATURES = VCP SDCARD_SPI
endif
TARGET_SRC = \
diff --git a/src/main/target/REVO/target.h b/src/main/target/REVO/target.h
index 8e1d18f688..b3f47c3ae8 100644
--- a/src/main/target/REVO/target.h
+++ b/src/main/target/REVO/target.h
@@ -159,6 +159,7 @@
// SDCARD support for AIRBOTF4SD
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC0
#define SDCARD_SPI_INSTANCE SPI3
diff --git a/src/main/target/REVO/target.mk b/src/main/target/REVO/target.mk
index b45407a446..b01f8931ab 100644
--- a/src/main/target/REVO/target.mk
+++ b/src/main/target/REVO/target.mk
@@ -1,6 +1,6 @@
F405_TARGETS += $(TARGET)
ifeq ($(TARGET), AIRBOTF4SD)
-FEATURES = VCP SDCARD
+FEATURES = VCP SDCARD_SPI
else
FEATURES = VCP ONBOARDFLASH
endif
diff --git a/src/main/target/RG_SSD_F3/target.h b/src/main/target/RG_SSD_F3/target.h
index 3183187686..7a355c7e74 100644
--- a/src/main/target/RG_SSD_F3/target.h
+++ b/src/main/target/RG_SSD_F3/target.h
@@ -69,6 +69,7 @@
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI1
diff --git a/src/main/target/RG_SSD_F3/target.mk b/src/main/target/RG_SSD_F3/target.mk
index 59b6ea1842..6598b60ee8 100644
--- a/src/main/target/RG_SSD_F3/target.mk
+++ b/src/main/target/RG_SSD_F3/target.mk
@@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
-FEATURES = VCP SDCARD
+FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
diff --git a/src/main/target/SIRINFPV/target.h b/src/main/target/SIRINFPV/target.h
index bbfb89bb05..16db889f40 100644
--- a/src/main/target/SIRINFPV/target.h
+++ b/src/main/target/SIRINFPV/target.h
@@ -143,6 +143,7 @@
#define RTC6705_CS_PIN PC14
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_GPIO SPI2_GPIO
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
diff --git a/src/main/target/SIRINFPV/target.mk b/src/main/target/SIRINFPV/target.mk
index d11e00c40d..57abe64cfa 100644
--- a/src/main/target/SIRINFPV/target.mk
+++ b/src/main/target/SIRINFPV/target.mk
@@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
-FEATURES = VCP SDCARD
+FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
diff --git a/src/main/target/SITL/target.mk b/src/main/target/SITL/target.mk
index 801acaf0a2..80f025cf99 100644
--- a/src/main/target/SITL/target.mk
+++ b/src/main/target/SITL/target.mk
@@ -1,5 +1,5 @@
SITL_TARGETS += $(TARGET)
-#FEATURES += SDCARD VCP
+FEATURES += #SDCARD_SPI VCP
TARGET_SRC = \
drivers/accgyro/accgyro_fake.c \
diff --git a/src/main/target/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h
index 67f4017e1b..c4f66c3e04 100644
--- a/src/main/target/SPRACINGF3EVO/target.h
+++ b/src/main/target/SPRACINGF3EVO/target.h
@@ -157,6 +157,7 @@
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2
diff --git a/src/main/target/SPRACINGF3EVO/target.mk b/src/main/target/SPRACINGF3EVO/target.mk
index bf60918251..89265f16e0 100644
--- a/src/main/target/SPRACINGF3EVO/target.mk
+++ b/src/main/target/SPRACINGF3EVO/target.mk
@@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
-FEATURES = VCP SDCARD
+FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
diff --git a/src/main/target/SPRACINGF3MINI/target.h b/src/main/target/SPRACINGF3MINI/target.h
index 45a2bf248d..7611c6ee78 100644
--- a/src/main/target/SPRACINGF3MINI/target.h
+++ b/src/main/target/SPRACINGF3MINI/target.h
@@ -179,6 +179,7 @@
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2
diff --git a/src/main/target/SPRACINGF3MINI/target.mk b/src/main/target/SPRACINGF3MINI/target.mk
index cbf1aa87f8..e20629f150 100644
--- a/src/main/target/SPRACINGF3MINI/target.mk
+++ b/src/main/target/SPRACINGF3MINI/target.mk
@@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
-FEATURES = VCP SDCARD
+FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
diff --git a/src/main/target/SPRACINGF3NEO/target.h b/src/main/target/SPRACINGF3NEO/target.h
index 4a04cffa54..e9e9406da5 100644
--- a/src/main/target/SPRACINGF3NEO/target.h
+++ b/src/main/target/SPRACINGF3NEO/target.h
@@ -140,6 +140,7 @@
#define SPI_SHARED_MAX7456_AND_RTC6705
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2
diff --git a/src/main/target/SPRACINGF3NEO/target.mk b/src/main/target/SPRACINGF3NEO/target.mk
index 3bb8199299..32ef98f4b3 100644
--- a/src/main/target/SPRACINGF3NEO/target.mk
+++ b/src/main/target/SPRACINGF3NEO/target.mk
@@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
-FEATURES = VCP SDCARD
+FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
diff --git a/src/main/target/SPRACINGF4EVO/target.h b/src/main/target/SPRACINGF4EVO/target.h
index 6b9442ad71..31088e6c48 100644
--- a/src/main/target/SPRACINGF4EVO/target.h
+++ b/src/main/target/SPRACINGF4EVO/target.h
@@ -148,6 +148,7 @@
#endif
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2
diff --git a/src/main/target/SPRACINGF4EVO/target.mk b/src/main/target/SPRACINGF4EVO/target.mk
index a41a03e1af..d44e5b07f4 100644
--- a/src/main/target/SPRACINGF4EVO/target.mk
+++ b/src/main/target/SPRACINGF4EVO/target.mk
@@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
-FEATURES = VCP SDCARD
+FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \
diff --git a/src/main/target/SPRACINGF4NEO/target.h b/src/main/target/SPRACINGF4NEO/target.h
index 580ce15c97..8d655f0ff6 100644
--- a/src/main/target/SPRACINGF4NEO/target.h
+++ b/src/main/target/SPRACINGF4NEO/target.h
@@ -161,6 +161,7 @@
//#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_ST0_HANDLER
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2
diff --git a/src/main/target/SPRACINGF4NEO/target.mk b/src/main/target/SPRACINGF4NEO/target.mk
index 6568f56a5b..11b2828f79 100644
--- a/src/main/target/SPRACINGF4NEO/target.mk
+++ b/src/main/target/SPRACINGF4NEO/target.mk
@@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
-FEATURES = VCP SDCARD
+FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \
diff --git a/src/main/target/SPRACINGF7DUAL/target.h b/src/main/target/SPRACINGF7DUAL/target.h
index 36f153a4d7..70427a3e2b 100644
--- a/src/main/target/SPRACINGF7DUAL/target.h
+++ b/src/main/target/SPRACINGF7DUAL/target.h
@@ -149,6 +149,7 @@
#define SPI3_MOSI_PIN PB5
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_SPI_INSTANCE SPI3
#define SDCARD_SPI_CS_PIN PC3
#define SDCARD_DMA_STREAM_TX_FULL DMA1_Stream7
diff --git a/src/main/target/SPRACINGF7DUAL/target.mk b/src/main/target/SPRACINGF7DUAL/target.mk
index 581846b461..e756fd03e9 100644
--- a/src/main/target/SPRACINGF7DUAL/target.mk
+++ b/src/main/target/SPRACINGF7DUAL/target.mk
@@ -1,5 +1,5 @@
F7X2RE_TARGETS += $(TARGET)
-FEATURES = VCP SDCARD
+FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_fake.c \
diff --git a/src/main/target/STM32F3DISCOVERY/target.mk b/src/main/target/STM32F3DISCOVERY/target.mk
index 8886e68e18..3b338c0e0a 100644
--- a/src/main/target/STM32F3DISCOVERY/target.mk
+++ b/src/main/target/STM32F3DISCOVERY/target.mk
@@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
-FEATURES = VCP SDCARD ONBOARDFLASH
+FEATURES = VCP SDCARD_SPI ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_fake.c \
diff --git a/src/main/target/STM32F4DISCOVERY/target.h b/src/main/target/STM32F4DISCOVERY/target.h
index cdb2039494..30046655c3 100644
--- a/src/main/target/STM32F4DISCOVERY/target.h
+++ b/src/main/target/STM32F4DISCOVERY/target.h
@@ -95,6 +95,7 @@
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN PD8
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5
diff --git a/src/main/target/STM32F4DISCOVERY/target.mk b/src/main/target/STM32F4DISCOVERY/target.mk
index c3619efdb4..3a09402a71 100644
--- a/src/main/target/STM32F4DISCOVERY/target.mk
+++ b/src/main/target/STM32F4DISCOVERY/target.mk
@@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
-FEATURES += VCP SDCARD MSC
+FEATURES += VCP SDCARD_SPI MSC
TARGET_SRC = \
drivers/accgyro/accgyro_fake.c \
diff --git a/src/main/target/STM32F7X2/target.h b/src/main/target/STM32F7X2/target.h
index a0b0fadc7b..f83d3e837c 100644
--- a/src/main/target/STM32F7X2/target.h
+++ b/src/main/target/STM32F7X2/target.h
@@ -69,6 +69,7 @@
#define USE_BARO_LPS
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define USE_I2C
#define USE_I2C_DEVICE_1
diff --git a/src/main/target/STM32F7X2/target.mk b/src/main/target/STM32F7X2/target.mk
index 4269ebdb17..4637331c0c 100644
--- a/src/main/target/STM32F7X2/target.mk
+++ b/src/main/target/STM32F7X2/target.mk
@@ -1,5 +1,5 @@
F7X2RE_TARGETS += $(TARGET)
-FEATURES += SDCARD VCP
+FEATURES += SDCARD_SPI VCP
TARGET_SRC = \
$(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \
diff --git a/src/main/target/UAVPNG030MINI/target.h b/src/main/target/UAVPNG030MINI/target.h
index 67cf69327d..4cd4538a9d 100644
--- a/src/main/target/UAVPNG030MINI/target.h
+++ b/src/main/target/UAVPNG030MINI/target.h
@@ -64,6 +64,7 @@
#if 0 // TODO: Enable SDCard and blackbox logging
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PE2
#define SDCARD_SPI_INSTANCE SPI2
diff --git a/src/main/target/VRRACE/target.h b/src/main/target/VRRACE/target.h
index 7828b6cfdc..e3a83ea6d8 100644
--- a/src/main/target/VRRACE/target.h
+++ b/src/main/target/VRRACE/target.h
@@ -55,6 +55,7 @@
#define MS5611_I2C_INSTANCE I2CDEV_1
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PD2
#define SDCARD_SPI_INSTANCE SPI2
diff --git a/src/main/target/WORMFC/target.mk b/src/main/target/WORMFC/target.mk
index 1a0a31d925..4fa1a426ed 100644
--- a/src/main/target/WORMFC/target.mk
+++ b/src/main/target/WORMFC/target.mk
@@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
-FEATURES += VCP SDIO
+FEATURES += VCP SDCARD_SDIO
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
diff --git a/src/main/target/YUPIF4/target.h b/src/main/target/YUPIF4/target.h
index 62599730f1..9f53f43330 100644
--- a/src/main/target/YUPIF4/target.h
+++ b/src/main/target/YUPIF4/target.h
@@ -84,6 +84,7 @@
// SD Card
#define USE_SDCARD
+#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PD2
#define SDCARD_SPI_INSTANCE SPI3
diff --git a/src/main/target/YUPIF4/target.mk b/src/main/target/YUPIF4/target.mk
index 8047b59f40..341ae64ee0 100644
--- a/src/main/target/YUPIF4/target.mk
+++ b/src/main/target/YUPIF4/target.mk
@@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
-FEATURES += SDCARD VCP
+FEATURES += SDCARD_SPI VCP
TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \
diff --git a/src/main/target/common_defaults_post.h b/src/main/target/common_defaults_post.h
index 9d675e5265..dd84c323dd 100644
--- a/src/main/target/common_defaults_post.h
+++ b/src/main/target/common_defaults_post.h
@@ -275,3 +275,22 @@
#define MAX_TIMER_PINMAP_COUNT 21 // Largest known for F405RG (OMNINXT)
#endif
#endif
+
+#ifdef USE_SDCARD
+#ifndef SDCARD_DETECT_PIN
+#define SDCARD_DETECT_PIN NONE
+#endif
+#ifndef SDCARD_SPI_CS_PIN
+#define SDCARD_SPI_CS_PIN NONE
+#endif
+#ifdef SDCARD_DETECT_INVERTED
+#define SDCARD_DETECT_IS_INVERTED 1
+#else
+#define SDCARD_DETECT_IS_INVERTED 0
+#endif
+#ifdef USE_SDCARD_SPI
+#ifndef SDCARD_SPI_INSTANCE
+#define SDCARD_SPI_INSTANCE NULL
+#endif
+#endif
+#endif