1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-20 23:05:19 +03:00

Add SDIO STDLIB driver

This commit is contained in:
Chris 2017-12-27 13:47:56 +00:00
parent 90210b7c54
commit 90adb18f22
3 changed files with 4151 additions and 0 deletions

View file

@ -0,0 +1,631 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include "platform.h"
#ifdef USE_SDCARD_SDIO
#include "drivers/nvic.h"
#include "drivers/io.h"
#include "drivers/dma.h"
#include "drivers/time.h"
#include "drivers/sdcard.h"
#include "drivers/sdcard_standard.h"
#include "drivers/sdio_stdlib.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 SDIO_DMA
volatile uint8_t TxDMA_Cplt;
volatile uint8_t RxDMA_Cplt;
#endif
#ifdef SDCARD_PROFILING
sdcard_profilerCallback_c profiler;
#endif
} sdcard_t;
static sdcard_t sdcard;
STATIC_ASSERT(sizeof(sdcardCSD_t) == 16, sdcard_csd_bitfields_didnt_pack_properly);
void sdcardInsertionDetectDeinit(void)
{
//Handled by the driver
return;
}
void sdcardInsertionDetectInit(void)
{
//Handled by the driver
return;
}
/**
* Detect if a SD card is physically present in the memory slot.
*/
bool sdcard_isInserted(void)
{
return SD_Detect();
}
/**
* 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;
}
/**
* 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)
{
SD_DeInit();
delay(200);
SD_Init();
sdcard.failureCount++;
if (sdcard.failureCount >= SDCARD_MAX_CONSECUTIVE_FAILURES || sdcard_isInserted() == SD_NOT_PRESENT) {
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 ret = SD_WaitReadOperation();
if (ret == SD_REQUEST_PENDING) {
return SDCARD_RECEIVE_BLOCK_IN_PROGRESS;
}
if (SD_GetStatus() != SD_TRANSFER_OK) {
return SDCARD_RECEIVE_ERROR;
}
return SDCARD_RECEIVE_SUCCESS;
}
static bool sdcard_receiveCID(void)
{
SD_CardInfo sdinfo;
SD_GetCardInfo(&sdinfo);
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 sdinfo;
SD_GetCardInfo(&sdinfo);
sdcard.metadata.numBlocks = sdinfo.CardCapacity / sdinfo.CardBlockSize;
return (bool) 1;
}
/**
* 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)
{
uint8_t ret = SD_GetStatus();
if (ret == SD_TRANSFER_OK) {
SD_CardInfo sdinfo;
SD_GetCardInfo(&sdinfo);
sdcard.version = (sdinfo.CardType) ? 2 : 1;
sdcard.highCapacity = (sdinfo.CardType == 2) ? 1 : 0;
}
// When card init is complete, the idle bit in the response becomes zero.
return (ret == SD_TRANSFER_OK) ? true : false;
}
/**
* Begin the initialization process for the SD card. This must be called first before any other sdcard_ routine.
*/
void sdcard_init(bool useDMA)
{
UNUSED(useDMA);
if (SD_Detect() == SD_PRESENT) {
if (SD_Init() != SD_OK) {
sdcard.state = SDCARD_STATE_NOT_PRESENT;
sdcard.failureCount++;
return;
}
} else {
sdcard.state = SDCARD_STATE_NOT_PRESENT;
sdcard.failureCount++;
return;
}
sdcard.operationStartTime = millis();
sdcard.state = SDCARD_STATE_RESET;
sdcard.failureCount = 0;
}
/*
* Returns true if the card is ready to accept read/write commands.
*/
static bool sdcard_isReady()
{
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()
{
sdcard.multiWriteBlocksRemain = 0;
// 8 dummy clocks to guarantee N_WR clocks between the last card response and this token
// Card may choose to raise a busy (non-0xFF) signal after at most N_BR (1 byte) delay
if (SD_GetStatus() == SD_TRANSFER_OK) {
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)
{
uint8_t initStatus;
UNUSED(initStatus);
#ifdef SDCARD_PROFILING
bool profilingComplete;
#endif
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 {
sdcard_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)) {
// sdcard_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_WaitWriteOperation() == 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_GetStatus() == SD_TRANSFER_OK) {
#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:
sdcard.multiWriteBlocksRemain = 0;
} else {
sdcard.state = SDCARD_STATE_READY;
}
#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.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
case SDCARD_RECEIVE_ERROR:
goto doMore;
break;
}
break;
case SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE:
if (SD_GetStatus() == SD_TRANSFER_OK) {
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)
{
#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;
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_WriteBlock(buffer, blockIndex * 512, 1) != 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.
*/
sdcard_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
*/
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;
}
}
// if (BSP_SD_Erase(blockIndex, blockCount * 512 + blockIndex)) {
sdcard.state = SDCARD_STATE_WRITING_MULTIPLE_BLOCKS;
sdcard.multiWriteBlocksRemain = blockCount;
sdcard.multiWriteNextBlock = blockIndex;
// Leave the card selected
return SDCARD_OPERATION_SUCCESS;
// } else {
// 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) {
return false;
}
#ifdef SDCARD_PROFILING
sdcard.pendingOperation.profileStartTime = micros();
#endif
// Standard size cards use byte addressing, high capacity cards use block addressing
uint8_t status = SD_ReadBlock(buffer, blockIndex * 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 {
sdcard_reset();
if (sdcard.pendingOperation.callback) {
sdcard.pendingOperation.callback(
SDCARD_BLOCK_OPERATION_READ,
sdcard.pendingOperation.blockIndex,
NULL,
sdcard.pendingOperation.callbackData
);
}
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

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,398 @@
/**
******************************************************************************
* @file stm324x9i_eval_sdio_sd.h
* @author MCD Application Team
* @version V1.0.3
* @date 13-November-2013
* @brief This file contains all the functions prototypes for the SD Card
* stm324x9i_eval_sdio_sd driver firmware library.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __SD_STDLIB_DRV
#define __SD_STDLIB_DRV
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f4xx.h"
#include "stm32f4xx_sdio.h"
#include "platform.h"
#include "drivers/dma.h"
typedef enum
{
/**
* @brief SDIO specific error defines
*/
SD_CMD_CRC_FAIL = (1), /*!< Command response received (but CRC check failed) */
SD_DATA_CRC_FAIL = (2), /*!< Data bock sent/received (CRC check Failed) */
SD_CMD_RSP_TIMEOUT = (3), /*!< Command response timeout */
SD_DATA_TIMEOUT = (4), /*!< Data time out */
SD_TX_UNDERRUN = (5), /*!< Transmit FIFO under-run */
SD_RX_OVERRUN = (6), /*!< Receive FIFO over-run */
SD_START_BIT_ERR = (7), /*!< Start bit not detected on all data signals in widE bus mode */
SD_CMD_OUT_OF_RANGE = (8), /*!< CMD'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_SDIO_DISABLED = (30),
SD_SDIO_FUNCTION_BUSY = (31),
SD_SDIO_FUNCTION_FAILED = (32),
SD_SDIO_UNKNOWN_FUNCTION = (33),
/**
* @brief Standard error defines
*/
SD_INTERNAL_ERROR,
SD_NOT_CONFIGURED,
SD_REQUEST_PENDING,
SD_REQUEST_NOT_APPLICABLE,
SD_INVALID_PARAMETER,
SD_UNSUPPORTED_FEATURE,
SD_UNSUPPORTED_HW,
SD_ERROR,
SD_OK = 0
} SD_Error;
/**
* @brief SDIO Transfer state
*/
typedef enum
{
SD_TRANSFER_OK = 0,
SD_TRANSFER_BUSY = 1,
SD_TRANSFER_ERROR
} SDTransferState;
/**
* @brief SD Card States
*/
typedef enum
{
SD_CARD_READY = ((uint32_t)0x00000001),
SD_CARD_IDENTIFICATION = ((uint32_t)0x00000002),
SD_CARD_STANDBY = ((uint32_t)0x00000003),
SD_CARD_TRANSFER = ((uint32_t)0x00000004),
SD_CARD_SENDING = ((uint32_t)0x00000005),
SD_CARD_RECEIVING = ((uint32_t)0x00000006),
SD_CARD_PROGRAMMING = ((uint32_t)0x00000007),
SD_CARD_DISCONNECTED = ((uint32_t)0x00000008),
SD_CARD_ERROR = ((uint32_t)0x000000FF)
}SDCardState;
/**
* @brief Card Specific Data: CSD Register
*/
typedef struct
{
__IO uint8_t CSDStruct; /*!< CSD structure */
__IO uint8_t SysSpecVersion; /*!< System specification version */
__IO uint8_t Reserved1; /*!< Reserved */
__IO uint8_t TAAC; /*!< Data read access-time 1 */
__IO uint8_t NSAC; /*!< Data read access-time 2 in CLK cycles */
__IO uint8_t MaxBusClkFrec; /*!< Max. bus clock frequency */
__IO uint16_t CardComdClasses; /*!< Card command classes */
__IO uint8_t RdBlockLen; /*!< Max. read data block length */
__IO uint8_t PartBlockRead; /*!< Partial blocks for read allowed */
__IO uint8_t WrBlockMisalign; /*!< Write block misalignment */
__IO uint8_t RdBlockMisalign; /*!< Read block misalignment */
__IO uint8_t DSRImpl; /*!< DSR implemented */
__IO uint8_t Reserved2; /*!< Reserved */
__IO uint32_t DeviceSize; /*!< Device Size */
__IO uint8_t MaxRdCurrentVDDMin; /*!< Max. read current @ VDD min */
__IO uint8_t MaxRdCurrentVDDMax; /*!< Max. read current @ VDD max */
__IO uint8_t MaxWrCurrentVDDMin; /*!< Max. write current @ VDD min */
__IO uint8_t MaxWrCurrentVDDMax; /*!< Max. write current @ VDD max */
__IO uint8_t DeviceSizeMul; /*!< Device size multiplier */
__IO uint8_t EraseGrSize; /*!< Erase group size */
__IO uint8_t EraseGrMul; /*!< Erase group size multiplier */
__IO uint8_t WrProtectGrSize; /*!< Write protect group size */
__IO uint8_t WrProtectGrEnable; /*!< Write protect group enable */
__IO uint8_t ManDeflECC; /*!< Manufacturer default ECC */
__IO uint8_t WrSpeedFact; /*!< Write speed factor */
__IO uint8_t MaxWrBlockLen; /*!< Max. write data block length */
__IO uint8_t WriteBlockPaPartial; /*!< Partial blocks for write allowed */
__IO uint8_t Reserved3; /*!< Reserded */
__IO uint8_t ContentProtectAppli; /*!< Content protection application */
__IO uint8_t FileFormatGrouop; /*!< File format group */
__IO uint8_t CopyFlag; /*!< Copy flag (OTP) */
__IO uint8_t PermWrProtect; /*!< Permanent write protection */
__IO uint8_t TempWrProtect; /*!< Temporary write protection */
__IO uint8_t FileFormat; /*!< File Format */
__IO uint8_t ECC; /*!< ECC code */
__IO uint8_t CSD_CRC; /*!< CSD CRC */
__IO uint8_t Reserved4; /*!< always 1*/
} SD_CSD;
/**
* @brief Card Identification Data: CID Register
*/
typedef struct
{
__IO uint8_t ManufacturerID; /*!< ManufacturerID */
__IO uint16_t OEM_AppliID; /*!< OEM/Application ID */
__IO uint32_t ProdName1; /*!< Product Name part1 */
__IO uint8_t ProdName2; /*!< Product Name part2*/
__IO uint8_t ProdRev; /*!< Product Revision */
__IO uint32_t ProdSN; /*!< Product Serial Number */
__IO uint8_t Reserved1; /*!< Reserved1 */
__IO uint16_t ManufactDate; /*!< Manufacturing Date */
__IO uint8_t CID_CRC; /*!< CID CRC */
__IO uint8_t Reserved2; /*!< always 1 */
} SD_CID;
/**
* @brief SD Card Status
*/
typedef struct
{
__IO uint8_t DAT_BUS_WIDTH;
__IO uint8_t SECURED_MODE;
__IO uint16_t SD_CARD_TYPE;
__IO uint32_t SIZE_OF_PROTECTED_AREA;
__IO uint8_t SPEED_CLASS;
__IO uint8_t PERFORMANCE_MOVE;
__IO uint8_t AU_SIZE;
__IO uint16_t ERASE_SIZE;
__IO uint8_t ERASE_TIMEOUT;
__IO uint8_t ERASE_OFFSET;
} SD_CardStatus;
/**
* @brief SD Card information
*/
typedef struct
{
SD_CSD SD_csd;
SD_CID SD_cid;
uint64_t CardCapacity; /*!< Card Capacity */
uint32_t CardBlockSize; /*!< Card Block Size */
uint16_t RCA;
uint8_t CardType;
} SD_CardInfo;
/**
* @brief SDIO Commands Index
*/
#define SD_CMD_GO_IDLE_STATE ((uint8_t)0)
#define SD_CMD_SEND_OP_COND ((uint8_t)1)
#define SD_CMD_ALL_SEND_CID ((uint8_t)2)
#define SD_CMD_SET_REL_ADDR ((uint8_t)3) /*!< SDIO_SEND_REL_ADDR for SD Card */
#define SD_CMD_SET_DSR ((uint8_t)4)
#define SD_CMD_SDIO_SEN_OP_COND ((uint8_t)5)
#define SD_CMD_HS_SWITCH ((uint8_t)6)
#define SD_CMD_SEL_DESEL_CARD ((uint8_t)7)
#define SD_CMD_HS_SEND_EXT_CSD ((uint8_t)8)
#define SD_CMD_SEND_CSD ((uint8_t)9)
#define SD_CMD_SEND_CID ((uint8_t)10)
#define SD_CMD_READ_DAT_UNTIL_STOP ((uint8_t)11) /*!< SD Card doesn't support it */
#define SD_CMD_STOP_TRANSMISSION ((uint8_t)12)
#define SD_CMD_SEND_STATUS ((uint8_t)13)
#define SD_CMD_HS_BUSTEST_READ ((uint8_t)14)
#define SD_CMD_GO_INACTIVE_STATE ((uint8_t)15)
#define SD_CMD_SET_BLOCKLEN ((uint8_t)16)
#define SD_CMD_READ_SINGLE_BLOCK ((uint8_t)17)
#define SD_CMD_READ_MULT_BLOCK ((uint8_t)18)
#define SD_CMD_HS_BUSTEST_WRITE ((uint8_t)19)
#define SD_CMD_WRITE_DAT_UNTIL_STOP ((uint8_t)20) /*!< SD Card doesn't support it */
#define SD_CMD_SET_BLOCK_COUNT ((uint8_t)23) /*!< SD Card doesn't support it */
#define SD_CMD_WRITE_SINGLE_BLOCK ((uint8_t)24)
#define SD_CMD_WRITE_MULT_BLOCK ((uint8_t)25)
#define SD_CMD_PROG_CID ((uint8_t)26) /*!< reserved for manufacturers */
#define SD_CMD_PROG_CSD ((uint8_t)27)
#define SD_CMD_SET_WRITE_PROT ((uint8_t)28)
#define SD_CMD_CLR_WRITE_PROT ((uint8_t)29)
#define SD_CMD_SEND_WRITE_PROT ((uint8_t)30)
#define SD_CMD_SD_ERASE_GRP_START ((uint8_t)32) /*!< To set the address of the first write
block to be erased. (For SD card only) */
#define SD_CMD_SD_ERASE_GRP_END ((uint8_t)33) /*!< To set the address of the last write block of the
continuous range to be erased. (For SD card only) */
#define SD_CMD_ERASE_GRP_START ((uint8_t)35) /*!< To set the address of the first write block to be erased.
(For MMC card only spec 3.31) */
#define SD_CMD_ERASE_GRP_END ((uint8_t)36) /*!< To set the address of the last write block of the
continuous range to be erased. (For MMC card only spec 3.31) */
#define SD_CMD_ERASE ((uint8_t)38)
#define SD_CMD_FAST_IO ((uint8_t)39) /*!< SD Card doesn't support it */
#define SD_CMD_GO_IRQ_STATE ((uint8_t)40) /*!< SD Card doesn't support it */
#define SD_CMD_LOCK_UNLOCK ((uint8_t)42)
#define SD_CMD_APP_CMD ((uint8_t)55)
#define SD_CMD_GEN_CMD ((uint8_t)56)
#define SD_CMD_NO_CMD ((uint8_t)64)
/**
* @brief Following commands are SD Card Specific commands.
* SDIO_APP_CMD should be sent before sending these commands.
*/
#define SD_CMD_APP_SD_SET_BUSWIDTH ((uint8_t)6) /*!< For SD Card only */
#define SD_CMD_SD_APP_STAUS ((uint8_t)13) /*!< For SD Card only */
#define SD_CMD_SD_APP_SEND_NUM_WRITE_BLOCKS ((uint8_t)22) /*!< For SD Card only */
#define SD_CMD_SD_APP_OP_COND ((uint8_t)41) /*!< For SD Card only */
#define SD_CMD_SD_APP_SET_CLR_CARD_DETECT ((uint8_t)42) /*!< For SD Card only */
#define SD_CMD_SD_APP_SEND_SCR ((uint8_t)51) /*!< For SD Card only */
#define SD_CMD_SDIO_RW_DIRECT ((uint8_t)52) /*!< For SD I/O Card only */
#define SD_CMD_SDIO_RW_EXTENDED ((uint8_t)53) /*!< For SD I/O Card only */
/**
* @brief Following commands are SD Card Specific security commands.
* SDIO_APP_CMD should be sent before sending these commands.
*/
#define SD_CMD_SD_APP_GET_MKB ((uint8_t)43) /*!< For SD Card only */
#define SD_CMD_SD_APP_GET_MID ((uint8_t)44) /*!< For SD Card only */
#define SD_CMD_SD_APP_SET_CER_RN1 ((uint8_t)45) /*!< For SD Card only */
#define SD_CMD_SD_APP_GET_CER_RN2 ((uint8_t)46) /*!< For SD Card only */
#define SD_CMD_SD_APP_SET_CER_RES2 ((uint8_t)47) /*!< For SD Card only */
#define SD_CMD_SD_APP_GET_CER_RES1 ((uint8_t)48) /*!< For SD Card only */
#define SD_CMD_SD_APP_SECURE_READ_MULTIPLE_BLOCK ((uint8_t)18) /*!< For SD Card only */
#define SD_CMD_SD_APP_SECURE_WRITE_MULTIPLE_BLOCK ((uint8_t)25) /*!< For SD Card only */
#define SD_CMD_SD_APP_SECURE_ERASE ((uint8_t)38) /*!< For SD Card only */
#define SD_CMD_SD_APP_CHANGE_SECURE_AREA ((uint8_t)49) /*!< For SD Card only */
#define SD_CMD_SD_APP_SECURE_WRITE_MKB ((uint8_t)48) /*!< For SD Card only */
/* Uncomment the following line to select the SDIO Data transfer mode */
#if !defined (SD_DMA_MODE) && !defined (SD_POLLING_MODE)
#define SD_DMA_MODE ((uint32_t)0x00000000)
/*#define SD_POLLING_MODE ((uint32_t)0x00000002)*/
#endif
/**
* @brief SD detection on its memory slot
*/
#define SD_PRESENT ((uint8_t)0x01)
#define SD_NOT_PRESENT ((uint8_t)0x00)
/**
* @brief SD detection IO pin
*/
#define SD_DETECT_PIN IO16_Pin_15
/**
* @brief Supported SD Memory Cards
*/
#define SDIO_STD_CAPACITY_SD_CARD_V1_1 ((uint32_t)0x00000000)
#define SDIO_STD_CAPACITY_SD_CARD_V2_0 ((uint32_t)0x00000001)
#define SDIO_HIGH_CAPACITY_SD_CARD ((uint32_t)0x00000002)
#define SDIO_MULTIMEDIA_CARD ((uint32_t)0x00000003)
#define SDIO_SECURE_DIGITAL_IO_CARD ((uint32_t)0x00000004)
#define SDIO_HIGH_SPEED_MULTIMEDIA_CARD ((uint32_t)0x00000005)
#define SDIO_SECURE_DIGITAL_IO_COMBO_CARD ((uint32_t)0x00000006)
#define SDIO_HIGH_CAPACITY_MMC_CARD ((uint32_t)0x00000007)
/**
* @brief SD FLASH SDIO Interface
*/
#define SDIO_FIFO_ADDRESS ((uint32_t)0x40012C80)
/**
* @brief SDIO Intialization Frequency (400KHz max)
*/
#define SDIO_INIT_CLK_DIV ((uint8_t)0x76)
/**
* @brief SDIO Data Transfer Frequency (25MHz max)
*/
#define SDIO_TRANSFER_CLK_DIV ((uint8_t)0x0)
#define SD_SDIO_DMA DMA2
#define SD_SDIO_DMA_CLK RCC_AHB1Periph_DMA2
#define SD_SDIO_DMA_STREAM3 3
#ifdef SD_SDIO_DMA_STREAM3
#define SD_SDIO_DMA_STREAM DMA2_Stream3
#define SD_SDIO_DMA_CHANNEL DMA_Channel_4
#define SD_SDIO_DMA_FLAG_FEIF DMA_FLAG_FEIF3
#define SD_SDIO_DMA_FLAG_DMEIF DMA_FLAG_DMEIF3
#define SD_SDIO_DMA_FLAG_TEIF DMA_FLAG_TEIF3
#define SD_SDIO_DMA_FLAG_HTIF DMA_FLAG_HTIF3
#define SD_SDIO_DMA_FLAG_TCIF DMA_FLAG_TCIF3
#define SD_SDIO_DMA_IRQn DMA2_Stream3_IRQn
#define SD_SDIO_DMA_IRQHANDLER DMA2_Stream3_IRQHandler
#elif defined SD_SDIO_DMA_STREAM6
#define SD_SDIO_DMA_STREAM DMA2_Stream6
#define SD_SDIO_DMA_CHANNEL DMA_Channel_4
#define SD_SDIO_DMA_FLAG_FEIF DMA_FLAG_FEIF6
#define SD_SDIO_DMA_FLAG_DMEIF DMA_FLAG_DMEIF6
#define SD_SDIO_DMA_FLAG_TEIF DMA_FLAG_TEIF6
#define SD_SDIO_DMA_FLAG_HTIF DMA_FLAG_HTIF6
#define SD_SDIO_DMA_FLAG_TCIF DMA_FLAG_TCIF6
#define SD_SDIO_DMA_IRQn DMA2_Stream6_IRQn
#define SD_SDIO_DMA_IRQHANDLER DMA2_Stream6_IRQHandler
#endif /* SD_SDIO_DMA_STREAM3 */
void SD_DeInit(void);
SD_Error SD_Init(void);
SDTransferState SD_GetStatus(void);
SDCardState SD_GetState(void);
uint8_t SD_Detect(void);
SD_Error SD_PowerON(void);
SD_Error SD_PowerOFF(void);
SD_Error SD_InitializeCards(void);
SD_Error SD_GetCardInfo(SD_CardInfo *cardinfo);
SD_Error SD_GetCardStatus(SD_CardStatus *cardstatus);
SD_Error SD_EnableWideBusOperation(uint32_t WideMode);
SD_Error SD_SelectDeselect(uint64_t addr);
SD_Error SD_ReadBlock(uint8_t *readbuff, uint64_t ReadAddr, uint16_t BlockSize);
SD_Error SD_ReadMultiBlocks(uint8_t *readbuff, uint64_t ReadAddr, uint16_t BlockSize, uint32_t NumberOfBlocks);
SD_Error SD_WriteBlock(uint8_t *writebuff, uint64_t WriteAddr, uint16_t BlockSize);
SD_Error SD_WriteMultiBlocks(uint8_t *writebuff, uint64_t WriteAddr, uint16_t BlockSize, uint32_t NumberOfBlocks);
SDTransferState SD_GetTransferState(void);
SD_Error SD_StopTransfer(void);
SD_Error SD_Erase(uint64_t startaddr, uint64_t endaddr);
SD_Error SD_SendStatus(uint32_t *pcardstatus);
SD_Error SD_SendSDStatus(uint32_t *psdstatus);
SD_Error SD_ProcessIRQSrc(void);
void SD_ProcessDMAIRQ(dmaChannelDescriptor_t * dma);
SD_Error SD_WaitReadOperation(void);
SD_Error SD_WaitWriteOperation(void);
SD_Error SD_HighSpeed(void);
#ifdef __cplusplus
}
#endif
#endif /* __SD_STDLIB_DRV */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/