1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-25 17:25:18 +03:00

[SDIO] Add support for SDIO to F7

This commit is contained in:
Konstantin (DigitalEntity) Sharlaimov 2019-07-16 12:46:54 +02:00
parent a2413ac6e1
commit d3b2ae2eac
22 changed files with 2510 additions and 78 deletions

View file

@ -159,7 +159,8 @@ MCU_COMMON_SRC = \
drivers/system_stm32f7xx.c \
drivers/serial_uart_stm32f7xx.c \
drivers/serial_softserial.c \
drivers/serial_uart_hal.c
drivers/serial_uart_hal.c \
drivers/sdcard/sdmmc_sdio_f7xx.c
MCU_EXCLUDES = \
drivers/bus_spi.c \

View file

@ -226,9 +226,10 @@ endif
ifneq ($(filter SDCARD,$(FEATURES)),)
TARGET_SRC += \
drivers/sdcard.c \
drivers/sdcard_spi.c \
drivers/sdcard_standard.c \
drivers/sdcard/sdcard.c \
drivers/sdcard/sdcard_spi.c \
drivers/sdcard/sdcard_sdio.c \
drivers/sdcard/sdcard_standard.c \
io/asyncfatfs/asyncfatfs.c \
io/asyncfatfs/fat_standard.c
endif

View file

@ -40,24 +40,20 @@ typedef void (*dmaCallbackHandlerFuncPtr)(DMA_t channelDescriptor);
typedef struct dmaChannelDescriptor_s {
dmaTag_t tag;
DMA_TypeDef* dma;
#if defined(STM32F4)
#if defined(STM32F4) || defined(STM32F7)
DMA_Stream_TypeDef* ref;
#elif defined(STM32F7)
DMA_Stream_TypeDef* ref;
DMA_HandleTypeDef hdma;
#else
DMA_Channel_TypeDef* ref;
#endif
dmaCallbackHandlerFuncPtr irqHandlerCallback;
uint32_t flagsShift;
IRQn_Type irqNumber;
uint32_t rcc;
uint32_t userParam;
resourceOwner_e owner;
uint8_t resourceIndex;
} dmaChannelDescriptor_t;
#if defined(STM32F4)
#if defined(STM32F4) || defined(STM32F7)
#define DEFINE_DMA_CHANNEL(d, s, f) { \
.tag = DMA_TAG(d, s, 0), \
@ -66,7 +62,6 @@ typedef struct dmaChannelDescriptor_s {
.irqHandlerCallback = NULL, \
.flagsShift = f, \
.irqNumber = DMA##d##_Stream##s##_IRQn, \
.rcc = RCC_AHB1Periph_DMA##d, \
.userParam = 0 \
}
@ -85,33 +80,7 @@ typedef struct dmaChannelDescriptor_s {
#define DMA_IT_DMEIF ((uint32_t)0x00000004)
#define DMA_IT_FEIF ((uint32_t)0x00000001)
#elif defined(STM32F7)
#define DEFINE_DMA_CHANNEL(d, s, f) { \
.tag = DMA_TAG(d, s, 0), \
.dma = DMA##d, \
.ref = DMA##d##_Stream##s, \
.irqHandlerCallback = NULL, \
.flagsShift = f, \
.irqNumber = DMA##d##_Stream##s##_IRQn, \
.rcc = RCC_AHB1ENR_DMA##d##EN, \
.userParam = 0 \
}
#define DEFINE_DMA_IRQ_HANDLER(d, s, i) void DMA ## d ## _Stream ## s ## _IRQHandler(void) {\
if (dmaDescriptors[i].irqHandlerCallback)\
dmaDescriptors[i].irqHandlerCallback(&dmaDescriptors[i]);\
}
#define DMA_CLEAR_FLAG(d, flag) if (d->flagsShift > 31) d->dma->HIFCR = (flag << (d->flagsShift - 32)); else d->dma->LIFCR = (flag << d->flagsShift)
#define DMA_GET_FLAG_STATUS(d, flag) (d->flagsShift > 31 ? d->dma->HISR & (flag << (d->flagsShift - 32)): d->dma->LISR & (flag << d->flagsShift))
#define DMA_IT_TCIF ((uint32_t)0x00000020)
#define DMA_IT_HTIF ((uint32_t)0x00000010)
#define DMA_IT_TEIF ((uint32_t)0x00000008)
#define DMA_IT_DMEIF ((uint32_t)0x00000004)
#define DMA_IT_FEIF ((uint32_t)0x00000001)
DMA_t dmaGetByRef(const DMA_Stream_TypeDef * ref);
#else // STM32F3
@ -122,7 +91,6 @@ typedef struct dmaChannelDescriptor_s {
.irqHandlerCallback = NULL, \
.flagsShift = f, \
.irqNumber = DMA##d##_Channel##c##_IRQn, \
.rcc = RCC_AHBPeriph_DMA##d, \
.userParam = 0 \
}
@ -138,12 +106,8 @@ typedef struct dmaChannelDescriptor_s {
#define DMA_IT_HTIF ((uint32_t)0x00000004)
#define DMA_IT_TEIF ((uint32_t)0x00000008)
#endif
DMA_t dmaGetByRef(const DMA_Channel_TypeDef * ref);
#if defined(STM32F4) || defined(STM32F7)
DMA_t dmaFindHandlerIdentifier(DMA_Stream_TypeDef* stream);
#else
DMA_t dmaFindHandlerIdentifier(DMA_Channel_TypeDef* channel);
#endif
DMA_t dmaGetByTag(dmaTag_t tag);

View file

@ -25,6 +25,7 @@
#include "common/utils.h"
#include "drivers/nvic.h"
#include "drivers/dma.h"
#include "drivers/rcc.h"
/*
* DMA descriptors.
@ -75,7 +76,12 @@ DMA_t dmaGetByTag(dmaTag_t tag)
void dmaEnableClock(DMA_t dma)
{
RCC_AHBPeriphClockCmd(dma->rcc, ENABLE);
if (dma->dma == DMA1) {
RCC_ClockCmd(RCC_AHB(DMA1), ENABLE);
}
else {
RCC_ClockCmd(RCC_AHB(DMA2), ENABLE);
}
}
resourceOwner_e dmaGetOwner(DMA_t dma)
@ -106,10 +112,10 @@ void dmaSetHandler(DMA_t dma, dmaCallbackHandlerFuncPtr callback, uint32_t prior
NVIC_Init(&NVIC_InitStructure);
}
DMA_t dmaFindHandlerIdentifier(DMA_Channel_TypeDef* channel)
DMA_t dmaGetByRef(const DMA_Channel_TypeDef * ref)
{
for (unsigned i = 0; i < (sizeof(dmaDescriptors) / sizeof(dmaDescriptors[0])); i++) {
if (channel == dmaDescriptors[i].ref) {
if (ref == dmaDescriptors[i].ref) {
return &dmaDescriptors[i];
}
}

View file

@ -25,6 +25,7 @@
#include "common/utils.h"
#include "drivers/nvic.h"
#include "drivers/dma.h"
#include "drivers/rcc.h"
/*
* DMA descriptors.
@ -83,7 +84,12 @@ DMA_t dmaGetByTag(dmaTag_t tag)
void dmaEnableClock(DMA_t dma)
{
RCC_AHB1PeriphClockCmd(dma->rcc, ENABLE);
if (dma->dma == DMA1) {
RCC_ClockCmd(RCC_AHB1(DMA1), ENABLE);
}
else {
RCC_ClockCmd(RCC_AHB1(DMA2), ENABLE);
}
}
resourceOwner_e dmaGetOwner(DMA_t dma)
@ -120,10 +126,10 @@ uint32_t dmaGetChannelByTag(dmaTag_t tag)
return dmaChannel[DMATAG_GET_CHANNEL(tag)];
}
DMA_t dmaFindHandlerIdentifier(DMA_Stream_TypeDef * stream)
DMA_t dmaGetByRef(const DMA_Stream_TypeDef* ref)
{
for (unsigned i = 0; i < (sizeof(dmaDescriptors) / sizeof(dmaDescriptors[0])); i++) {
if (stream == dmaDescriptors[i].ref) {
if (ref == dmaDescriptors[i].ref) {
return &dmaDescriptors[i];
}
}

View file

@ -24,6 +24,7 @@
#include "common/utils.h"
#include "drivers/nvic.h"
#include "drivers/dma.h"
#include "drivers/rcc.h"
/*
* DMA descriptors.
@ -82,13 +83,12 @@ DMA_t dmaGetByTag(dmaTag_t tag)
void dmaEnableClock(DMA_t dma)
{
do {
__IO uint32_t tmpreg;
SET_BIT(RCC->AHB1ENR, dma->rcc);
/* Delay after an RCC peripheral clock enabling */
tmpreg = READ_BIT(RCC->AHB1ENR, dma->rcc);
UNUSED(tmpreg);
} while (0);
if (dma->dma == DMA1) {
RCC_ClockCmd(RCC_AHB1(DMA1), ENABLE);
}
else {
RCC_ClockCmd(RCC_AHB1(DMA2), ENABLE);
}
}
resourceOwner_e dmaGetOwner(DMA_t dma)
@ -119,3 +119,14 @@ uint32_t dmaGetChannelByTag(dmaTag_t tag)
static const uint32_t dmaChannel[8] = { DMA_CHANNEL_0, DMA_CHANNEL_1, DMA_CHANNEL_2, DMA_CHANNEL_3, DMA_CHANNEL_4, DMA_CHANNEL_5, DMA_CHANNEL_6, DMA_CHANNEL_7 };
return dmaChannel[DMATAG_GET_CHANNEL(tag)];
}
DMA_t dmaGetByRef(const DMA_Stream_TypeDef* ref)
{
for (unsigned i = 0; i < (sizeof(dmaDescriptors) / sizeof(dmaDescriptors[0])); i++) {
if (ref == dmaDescriptors[i].ref) {
return &dmaDescriptors[i];
}
}
return NULL;
}

View file

@ -30,9 +30,9 @@
#include "drivers/io.h"
#include "drivers/bus.h"
#include "drivers/sdcard.h"
#include "drivers/sdcard_impl.h"
#include "drivers/sdcard_standard.h"
#include "drivers/sdcard/sdcard.h"
#include "drivers/sdcard/sdcard_impl.h"
#include "drivers/sdcard/sdcard_standard.h"
#include "scheduler/protothreads.h"

View file

@ -27,8 +27,8 @@
#include "drivers/bus_spi.h"
#include "drivers/time.h"
#include "drivers/sdcard.h"
#include "drivers/sdcard_standard.h"
#include "drivers/sdcard/sdcard.h"
#include "drivers/sdcard/sdcard_standard.h"
#define SDCARD_TIMEOUT_INIT_MILLIS 200
#define SDCARD_MAX_CONSECUTIVE_FAILURES 8
@ -50,8 +50,6 @@ typedef enum {
} sdcardState_e;
typedef struct sdcard_t {
busDevice_t * dev;
struct {
uint8_t *buffer;
uint32_t blockIndex;
@ -76,6 +74,14 @@ typedef struct sdcard_t {
sdcardCSD_t csd;
IO_t cardDetectPin;
#if defined(USE_SDCARD_SPI)
busDevice_t * dev;
#endif
#if defined(USE_SDCARD_SDIO)
DMA_t dma;
#endif
} sdcard_t;
extern sdcard_t sdcard;

View file

@ -0,0 +1,613 @@
/*
* This file is part of INAV, Cleanflight and Betaflight.
*
* INAV, Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
/* Adaptation of original driver to SDIO: Chris Hockuba (https://github.com/conkerkh) */
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include "platform.h"
#include "build/debug.h"
#include "common/utils.h"
#include "drivers/time.h"
#include "drivers/nvic.h"
#include "drivers/io.h"
#include "drivers/bus.h"
#include "drivers/bus_spi.h"
#include "drivers/dma.h"
#include "drivers/sdcard/sdcard.h"
#include "drivers/sdcard/sdcard_impl.h"
#include "drivers/sdcard/sdcard_standard.h"
#include "drivers/sdcard/sdmmc_sdio.h"
#include "scheduler/protothreads.h"
#ifdef USE_SDCARD_SDIO
//#define USE_SDCARD_SDIO_CACHE
#if !defined(SDCARD_SDIO_DMA)
#define SDCARD_SDIO_DMA DMA_TAG(2,3,4)
#endif
#if defined(USE_SDCARD_SDIO_CACHE)
// 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)));
uint32_t cacheCount = 0;
void cache_write(uint8_t *buffer)
{
if (cacheCount == sizeof(writeCache)) {
// Prevents overflow
return;
}
memcpy(&writeCache[cacheCount], buffer, 512);
cacheCount += 512;
}
uint16_t cache_getCount(void)
{
return (cacheCount / 512);
}
void cache_reset(void)
{
cacheCount = 0;
}
#endif
/**
* 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!)
*/
static bool sdcardSdio_isFunctional(void)
{
return sdcard.state != SDCARD_STATE_NOT_PRESENT;
}
/**
* 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 sdcardSdio_reset(void)
{
if (SD_Init() != 0) {
sdcard.failureCount++;
if (sdcard.failureCount >= SDCARD_MAX_CONSECUTIVE_FAILURES || !sdcard_isInserted()) {
sdcard.state = SDCARD_STATE_NOT_PRESENT;
} else {
sdcard.operationStartTime = millis();
sdcard.state = SDCARD_STATE_RESET;
}
}
}
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)
{
UNUSED(buffer);
UNUSED(count);
SD_Error_t ret = SD_CheckRead();
if (ret == SD_BUSY) {
return SDCARD_RECEIVE_BLOCK_IN_PROGRESS;
}
if (SD_GetState() != true) {
return SDCARD_RECEIVE_ERROR;
}
return SDCARD_RECEIVE_SUCCESS;
}
static bool sdcard_receiveCID(void)
{
SD_CardInfo_t *sdinfo = &SD_CardInfo;
SD_Error_t error = SD_GetCardInfo();
if (error) {
return false;
}
sdcard.metadata.manufacturerID = sdinfo->SD_cid.ManufacturerID;
sdcard.metadata.oemID = sdinfo->SD_cid.OEM_AppliID;
sdcard.metadata.productName[0] = (sdinfo->SD_cid.ProdName1 & 0xFF000000) >> 24;
sdcard.metadata.productName[1] = (sdinfo->SD_cid.ProdName1 & 0x00FF0000) >> 16;
sdcard.metadata.productName[2] = (sdinfo->SD_cid.ProdName1 & 0x0000FF00) >> 8;
sdcard.metadata.productName[3] = (sdinfo->SD_cid.ProdName1 & 0x000000FF) >> 0;
sdcard.metadata.productName[4] = sdinfo->SD_cid.ProdName2;
sdcard.metadata.productRevisionMajor = sdinfo->SD_cid.ProdRev >> 4;
sdcard.metadata.productRevisionMinor = sdinfo->SD_cid.ProdRev & 0x0F;
sdcard.metadata.productSerial = sdinfo->SD_cid.ProdSN;
sdcard.metadata.productionYear = (((sdinfo->SD_cid.ManufactDate & 0x0F00) >> 8) | ((sdinfo->SD_cid.ManufactDate & 0xFF) >> 4)) + 2000;
sdcard.metadata.productionMonth = sdinfo->SD_cid.ManufactDate & 0x000F;
return true;
}
static bool sdcard_fetchCSD(void)
{
/* 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!
*/
SD_CardInfo_t *sdinfo = &SD_CardInfo;
SD_Error_t error;
error = SD_GetCardInfo();
if (error) {
return false;
}
sdcard.metadata.numBlocks = sdinfo->CardCapacity;
return true;
}
/**
* 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)
{
if (SD_GetState()) {
SD_CardType_t *sdtype = &SD_CardType;
SD_Error_t errorState = SD_GetCardInfo();
if (errorState != SD_OK) {
return false;
}
sdcard.version = (*sdtype) ? 2 : 1;
sdcard.highCapacity = (*sdtype == 2) ? 1 : 0;
return true;
}
// When card init is complete, the idle bit in the response becomes zero.
return false;
}
/*
* 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;
#if defined(USE_SDCARD_SDIO_CACHE)
cache_reset();
#endif
// Card may choose to raise a busy (non-0xFF) signal after at most N_BR (1 byte) delay
if (SD_GetState()) {
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.
*/
static bool sdcardSdio_poll(void)
{
if (!sdcard.dma) {
sdcard.state = SDCARD_STATE_NOT_PRESENT;
return false;
}
doMore:
switch (sdcard.state) {
case SDCARD_STATE_RESET:
//HAL Takes care of voltage crap.
sdcard.state = SDCARD_STATE_CARD_INIT_IN_PROGRESS;
goto doMore;
break;
case SDCARD_STATE_CARD_INIT_IN_PROGRESS:
if (sdcard_checkInitDone()) {
// Now fetch the CSD and CID registers
if (sdcard_fetchCSD()) {
sdcard.state = SDCARD_STATE_INITIALIZATION_RECEIVE_CID;
goto doMore;
} else {
sdcardSdio_reset();
goto doMore;
}
}
break;
case SDCARD_STATE_INITIALIZATION_RECEIVE_CID:
if (sdcard_receiveCID()) {
/* 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 && SDMMC_CmdBlockLength(_HSD.Instance, SDCARD_BLOCK_SIZE)) {
// sdcardSdio_reset();
// goto doMore;
// }
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?
if (SD_CheckWrite() == SD_OK) {
// 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);
}
}
break;
case SDCARD_STATE_WAITING_FOR_WRITE:
if (SD_GetState()) {
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++;
#if defined(USE_SDCARD_SDIO_CACHE)
cache_reset();
#endif
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:
sdcard_endWriteBlocks();
} else {
sdcard.state = SDCARD_STATE_READY;
}
} 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.
*/
sdcardSdio_reset();
goto doMore;
}
break;
case SDCARD_STATE_READING:
switch (sdcard_receiveDataBlock(sdcard.pendingOperation.buffer, SDCARD_BLOCK_SIZE)) {
case SDCARD_RECEIVE_SUCCESS:
sdcard.state = SDCARD_STATE_READY;
sdcard.failureCount = 0; // Assume the card is good if it can complete a read
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
case SDCARD_RECEIVE_ERROR:
goto doMore;
break;
}
break;
case SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE:
if (SD_GetState()) {
sdcard.state = SDCARD_STATE_READY;
} else if (millis() > sdcard.operationStartTime + SDCARD_TIMEOUT_WRITE_MSEC) {
sdcardSdio_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) {
sdcardSdio_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
*/
static sdcardOperationStatus_e sdcardSdio_writeBlock(uint32_t blockIndex, uint8_t *buffer, sdcard_operationCompleteCallback_c callback, uint32_t callbackData)
{
#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:
break;
default:
return SDCARD_OPERATION_BUSY;
}
sdcard.pendingOperation.buffer = buffer;
sdcard.pendingOperation.blockIndex = blockIndex;
unsigned block_count = 1;
#if defined(USE_SDCARD_SDIO_CACHE)
if ((cache_getCount() < FATFS_BLOCK_CACHE_SIZE) && (sdcard.multiWriteBlocksRemain != 0)) {
cache_write(buffer);
if (cache_getCount() == FATFS_BLOCK_CACHE_SIZE || sdcard.multiWriteBlocksRemain == 1) {
//Relocate buffer and recalculate block index
buffer = (uint8_t*)writeCache;
blockIndex -= cache_getCount() - 1;
block_count = cache_getCount();
} else {
sdcard.multiWriteBlocksRemain--;
sdcard.multiWriteNextBlock++;
sdcard.state = SDCARD_STATE_READY;
return SDCARD_OPERATION_SUCCESS;
}
}
#endif
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;
if (SD_WriteBlocks_DMA(blockIndex, (uint32_t*) buffer, 512, block_count) != SD_OK) {
/* 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.
*/
sdcardSdio_reset();
// Announce write failure:
if (sdcard.pendingOperation.callback) {
sdcard.pendingOperation.callback(SDCARD_BLOCK_OPERATION_WRITE, sdcard.pendingOperation.blockIndex, NULL, sdcard.pendingOperation.callbackData);
}
return SDCARD_OPERATION_FAILURE;
}
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
*/
static sdcardOperationStatus_e sdcardSdio_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.state = SDCARD_STATE_WRITING_MULTIPLE_BLOCKS;
sdcard.multiWriteBlocksRemain = blockCount;
sdcard.multiWriteNextBlock = blockIndex;
return SDCARD_OPERATION_SUCCESS;
}
/**
* 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).
*/
static bool sdcardSdio_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;
}
}
// Standard size cards use byte addressing, high capacity cards use block addressing
uint8_t status = SD_ReadBlocks_DMA(blockIndex, (uint32_t*) buffer, 512, 1);
if (status == SD_OK) {
sdcard.pendingOperation.buffer = buffer;
sdcard.pendingOperation.blockIndex = blockIndex;
sdcard.pendingOperation.callback = callback;
sdcard.pendingOperation.callbackData = callbackData;
sdcard.state = SDCARD_STATE_READING;
sdcard.operationStartTime = millis();
return true;
} else {
sdcardSdio_reset();
if (sdcard.pendingOperation.callback) {
sdcard.pendingOperation.callback(
SDCARD_BLOCK_OPERATION_READ,
sdcard.pendingOperation.blockIndex,
NULL,
sdcard.pendingOperation.callbackData
);
}
return false;
}
}
/**
* Begin the initialization process for the SD card. This must be called first before any other sdcard_ routine.
*/
void sdcardSdio_init(void)
{
sdcard.dma = dmaGetByTag(SDCARD_SDIO_DMA);
if (!sdcard.dma) {
sdcard.state = SDCARD_STATE_NOT_PRESENT;
return;
}
// Check if somebody already occupies this DMA channel
if (dmaGetOwner(sdcard.dma) != OWNER_FREE) {
sdcard.dma = NULL;
sdcard.state = SDCARD_STATE_NOT_PRESENT;
return;
}
if (!SD_Initialize_LL(sdcard.dma->ref)) {
sdcard.dma = NULL;
sdcard.state = SDCARD_STATE_NOT_PRESENT;
return;
}
// We don't support hot insertion
if (!sdcard_isInserted()) {
sdcard.state = SDCARD_STATE_NOT_PRESENT;
return;
}
if (SD_Init() != 0) {
sdcard.state = SDCARD_STATE_NOT_PRESENT;
return;
}
sdcard.operationStartTime = millis();
sdcard.state = SDCARD_STATE_RESET;
sdcard.failureCount = 0;
}
/**
* Returns true if the SD card has successfully completed its startup procedures.
*/
static bool sdcardSdio_isInitialized(void)
{
return sdcard.state >= SDCARD_STATE_READY;
}
static const sdcardMetadata_t* sdcardSdio_getMetadata(void)
{
return &sdcard.metadata;
}
sdcardVTable_t sdcardSdioVTable = {
.init = &sdcardSdio_init,
.readBlock = &sdcardSdio_readBlock,
.beginWriteBlocks = &sdcardSdio_beginWriteBlocks,
.writeBlock = &sdcardSdio_writeBlock,
.poll = &sdcardSdio_poll,
.isFunctional = &sdcardSdio_isFunctional,
.isInitialized = &sdcardSdio_isInitialized,
.getMetadata = &sdcardSdio_getMetadata,
};
#endif

View file

@ -32,9 +32,9 @@
#include "drivers/bus.h"
#include "drivers/bus_spi.h"
#include "drivers/sdcard.h"
#include "drivers/sdcard_impl.h"
#include "drivers/sdcard_standard.h"
#include "drivers/sdcard/sdcard.h"
#include "drivers/sdcard/sdcard_impl.h"
#include "drivers/sdcard/sdcard_standard.h"
#include "scheduler/protothreads.h"

View file

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

File diff suppressed because it is too large Load diff

View file

@ -25,9 +25,6 @@
#include "drivers/io.h"
#include "drivers/time.h"
#include "usb_io.h"
#include "sdcard.h"
#ifdef USB_DETECT_PIN
static IO_t usbDetectPin = IO_NONE;

View file

@ -58,7 +58,7 @@ extern uint8_t __config_end;
#include "drivers/io_impl.h"
#include "drivers/osd_symbols.h"
#include "drivers/rx_pwm.h"
#include "drivers/sdcard.h"
#include "drivers/sdcard/sdcard.h"
#include "drivers/sensor.h"
#include "drivers/serial.h"
#include "drivers/stack_check.h"

View file

@ -61,7 +61,6 @@
#include "drivers/pwm_output.h"
#include "drivers/pwm_output.h"
#include "drivers/rx_pwm.h"
#include "drivers/sdcard.h"
#include "drivers/sensor.h"
#include "drivers/serial.h"
#include "drivers/serial_softserial.h"
@ -77,6 +76,7 @@
#include "drivers/io_pca9685.h"
#include "drivers/vtx_rtc6705.h"
#include "drivers/vtx_common.h"
#include "drivers/sdcard/sdcard.h"
#include "fc/cli.h"
#include "fc/config.h"

View file

@ -45,7 +45,7 @@
#include "drivers/osd.h"
#include "drivers/osd_symbols.h"
#include "drivers/pwm_mapping.h"
#include "drivers/sdcard.h"
#include "drivers/sdcard/sdcard.h"
#include "drivers/serial.h"
#include "drivers/system.h"
#include "drivers/time.h"

View file

@ -30,7 +30,7 @@
#include "asyncfatfs.h"
#include "fat_standard.h"
#include "drivers/sdcard.h"
#include "drivers/sdcard/sdcard.h"
#ifdef AFATFS_DEBUG
#define ONLY_EXPOSE_FOR_TESTING

View file

@ -163,10 +163,11 @@
#define SERIALRX_UART SERIAL_PORT_USART6
// *************** SPI3 SD BLACKBOX*******************
//#define USE_SDCARD
//#define USE_SDCARD_SDIO
#define SDCARD_SDIO_DMA_OPT 0 // D(2,3,4)
//#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define USE_SDCARD
#define USE_SDCARD_SDIO
#define SDCARD_SDIO_DMA DMA_TAG(2,3,4)
#define SDCARD_SDIO_4BIT
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
// *************** ADC *****************************
#define USE_ADC

View file

@ -281,9 +281,12 @@
BUSDEV_REGISTER_SPI(busdev_sdcard_spi, DEVHW_SDCARD, SDCARD_SPI_BUS, SDCARD_CS_PIN, NONE, DEVFLAGS_USE_MANUAL_DEVICE_SELECT | DEVFLAGS_SPI_MODE_0);
#endif
/*
// FIXME(digitalentity): This is unnecessary at the moment as SDIO is not part of BusDevice infrastructure
#if defined(USE_SDCARD) && defined(USE_SDCARD_SDIO)
BUSDEV_REGISTER_SDIO(busdev_sdcard_sdio,DEVHW_SDCARD, SDCARD_SDIO_BUS, SDCARD_CS_PIN, NONE, DEVFLAGS_USE_MANUAL_DEVICE_SELECT);
#endif
*/
#if defined(USE_OLED_UG2864)
#if !defined(UG2864_I2C_BUS)