SDIO rewrite in baremetal, fixes for WORMFC. (#5441)
* SDIO rewrite in baremetal, fixes for WORMFC. * Fix identation, move LED TIM * Fix identation
This commit is contained in:
parent
eb70859e4a
commit
c182748dbb
|
@ -61,5 +61,6 @@ const char * const debugModeNames[DEBUG_COUNT] = {
|
|||
"LIDAR_TF",
|
||||
"CORE_TEMP",
|
||||
"RUNAWAY_TAKEOFF",
|
||||
"SDIO",
|
||||
"CURRENT_SENSOR",
|
||||
};
|
||||
|
|
|
@ -79,6 +79,7 @@ typedef enum {
|
|||
DEBUG_LIDAR_TF,
|
||||
DEBUG_CORE_TEMP,
|
||||
DEBUG_RUNAWAY_TAKEOFF,
|
||||
DEBUG_SDIO,
|
||||
DEBUG_CURRENT,
|
||||
DEBUG_COUNT
|
||||
} debugType_e;
|
||||
|
|
|
@ -13,6 +13,9 @@
|
|||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* Adaptation of original driver to SDIO: Chris Hockuba (https://github.com/conkerkh)
|
||||
*
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
|
@ -21,6 +24,7 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#define USE_SDCARD_SDIO
|
||||
#ifdef USE_SDCARD_SDIO
|
||||
|
||||
#include "drivers/nvic.h"
|
||||
|
@ -32,7 +36,7 @@
|
|||
#include "drivers/sdcard.h"
|
||||
#include "drivers/sdcard_standard.h"
|
||||
|
||||
#include "drivers/sdio_stdlib.h"
|
||||
#include "drivers/sdmmc_sdio.h"
|
||||
|
||||
#ifdef AFATFS_USE_INTROSPECTIVE_LOGGING
|
||||
#define SDCARD_PROFILING
|
||||
|
@ -86,14 +90,13 @@ typedef struct sdcard_t {
|
|||
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
|
||||
bool enabled;
|
||||
IO_t cardDetectPin;
|
||||
dmaIdentifier_e dma;
|
||||
uint8_t dmaChannel;
|
||||
} sdcard_t;
|
||||
|
||||
static sdcard_t sdcard;
|
||||
|
@ -102,14 +105,18 @@ STATIC_ASSERT(sizeof(sdcardCSD_t) == 16, sdcard_csd_bitfields_didnt_pack_properl
|
|||
|
||||
void sdcardInsertionDetectDeinit(void)
|
||||
{
|
||||
//Handled by the driver
|
||||
return;
|
||||
if (sdcard.cardDetectPin) {
|
||||
IOInit(sdcard.cardDetectPin, OWNER_FREE, 0);
|
||||
IOConfigGPIO(sdcard.cardDetectPin, IOCFG_IN_FLOATING);
|
||||
}
|
||||
}
|
||||
|
||||
void sdcardInsertionDetectInit(void)
|
||||
{
|
||||
//Handled by the driver
|
||||
return;
|
||||
if (sdcard.cardDetectPin) {
|
||||
IOInit(sdcard.cardDetectPin, OWNER_SDCARD_DETECT, 0);
|
||||
IOConfigGPIO(sdcard.cardDetectPin, IOCFG_IPU);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -117,7 +124,11 @@ void sdcardInsertionDetectInit(void)
|
|||
*/
|
||||
bool sdcard_isInserted(void)
|
||||
{
|
||||
return SD_Detect();
|
||||
bool ret = true;
|
||||
if (sdcard.cardDetectPin) {
|
||||
ret = IORead(sdcard.cardDetectPin) == 0;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -137,16 +148,14 @@ bool sdcard_isFunctional(void)
|
|||
*/
|
||||
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;
|
||||
if (SD_Init() != 0) {
|
||||
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;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -165,13 +174,13 @@ static sdcardReceiveBlockStatus_e sdcard_receiveDataBlock(uint8_t *buffer, int c
|
|||
{
|
||||
UNUSED(buffer);
|
||||
UNUSED(count);
|
||||
SD_Error ret = SD_WaitReadOperation();
|
||||
SD_Error_t ret = SD_CheckRead();
|
||||
|
||||
if (ret == SD_REQUEST_PENDING) {
|
||||
if (ret == SD_BUSY) {
|
||||
return SDCARD_RECEIVE_BLOCK_IN_PROGRESS;
|
||||
}
|
||||
|
||||
if (SD_GetStatus() != SD_TRANSFER_OK) {
|
||||
if (SD_GetState() != true) {
|
||||
return SDCARD_RECEIVE_ERROR;
|
||||
}
|
||||
|
||||
|
@ -180,21 +189,24 @@ static sdcardReceiveBlockStatus_e sdcard_receiveDataBlock(uint8_t *buffer, int c
|
|||
|
||||
static bool sdcard_receiveCID(void)
|
||||
{
|
||||
SD_CardInfo sdinfo;
|
||||
SD_GetCardInfo(&sdinfo);
|
||||
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;
|
||||
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;
|
||||
}
|
||||
|
@ -204,11 +216,15 @@ 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);
|
||||
SD_CardInfo_t *sdinfo = &SD_CardInfo;
|
||||
SD_Error_t error;
|
||||
error = SD_GetCardInfo();
|
||||
if (error) {
|
||||
return false;
|
||||
}
|
||||
|
||||
sdcard.metadata.numBlocks = sdinfo.CardCapacity / sdinfo.CardBlockSize;
|
||||
return (bool) 1;
|
||||
sdcard.metadata.numBlocks = sdinfo->CardCapacity;
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -218,18 +234,17 @@ static bool sdcard_fetchCSD(void)
|
|||
*/
|
||||
static bool sdcard_checkInitDone(void)
|
||||
{
|
||||
uint8_t ret = SD_GetStatus();
|
||||
if (SD_GetState()) {
|
||||
SD_CardType_t *sdtype = &SD_CardType;
|
||||
SD_GetCardInfo();
|
||||
|
||||
if (ret == SD_TRANSFER_OK) {
|
||||
SD_CardInfo sdinfo;
|
||||
SD_GetCardInfo(&sdinfo);
|
||||
|
||||
sdcard.version = (sdinfo.CardType) ? 2 : 1;
|
||||
sdcard.highCapacity = (sdinfo.CardType == 2) ? 1 : 0;
|
||||
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 (ret == SD_TRANSFER_OK) ? true : false;
|
||||
return false;
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -237,9 +252,24 @@ static bool sdcard_checkInitDone(void)
|
|||
*/
|
||||
void sdcard_init(const sdcardConfig_t *config)
|
||||
{
|
||||
UNUSED(config);
|
||||
if (SD_Detect() == SD_PRESENT) {
|
||||
if (SD_Init() != SD_OK) {
|
||||
sdcard.enabled = config->enabled;
|
||||
if (!sdcard.enabled) {
|
||||
sdcard.state = SDCARD_STATE_NOT_PRESENT;
|
||||
return;
|
||||
}
|
||||
sdcard.dma = config->dmaIdentifier;
|
||||
if (sdcard.dma == 0) {
|
||||
sdcard.state = SDCARD_STATE_NOT_PRESENT;
|
||||
return;
|
||||
}
|
||||
if (config->cardDetectTag) {
|
||||
sdcard.cardDetectPin = IOGetByTag(config->cardDetectTag);
|
||||
} else {
|
||||
sdcard.cardDetectPin = IO_NONE;
|
||||
}
|
||||
SD_Initialize_LL(dmaGetRefByIdentifier(sdcard.dma));
|
||||
if (SD_IsDetected()) {
|
||||
if (SD_Init() != 0) {
|
||||
sdcard.state = SDCARD_STATE_NOT_PRESENT;
|
||||
sdcard.failureCount++;
|
||||
return;
|
||||
|
@ -280,7 +310,7 @@ static sdcardOperationStatus_e sdcard_endWriteBlocks()
|
|||
// 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) {
|
||||
if (SD_GetState()) {
|
||||
sdcard.state = SDCARD_STATE_READY;
|
||||
return SDCARD_OPERATION_SUCCESS;
|
||||
} else {
|
||||
|
@ -297,8 +327,10 @@ static sdcardOperationStatus_e sdcard_endWriteBlocks()
|
|||
*/
|
||||
bool sdcard_poll(void)
|
||||
{
|
||||
uint8_t initStatus;
|
||||
UNUSED(initStatus);
|
||||
if (!sdcard.enabled) {
|
||||
sdcard.state = SDCARD_STATE_NOT_PRESENT;
|
||||
return false;
|
||||
}
|
||||
|
||||
#ifdef SDCARD_PROFILING
|
||||
bool profilingComplete;
|
||||
|
@ -343,7 +375,7 @@ bool sdcard_poll(void)
|
|||
break;
|
||||
case SDCARD_STATE_SENDING_WRITE:
|
||||
// Have we finished sending the write yet?
|
||||
if (SD_WaitWriteOperation() == SD_OK) {
|
||||
if (SD_CheckWrite() == SD_OK) {
|
||||
|
||||
// The SD card is now busy committing that write to the card
|
||||
sdcard.state = SDCARD_STATE_WAITING_FOR_WRITE;
|
||||
|
@ -356,7 +388,7 @@ bool sdcard_poll(void)
|
|||
}
|
||||
break;
|
||||
case SDCARD_STATE_WAITING_FOR_WRITE:
|
||||
if (SD_GetStatus() == SD_TRANSFER_OK) {
|
||||
if (SD_GetState()) {
|
||||
#ifdef SDCARD_PROFILING
|
||||
profilingComplete = true;
|
||||
#endif
|
||||
|
@ -370,7 +402,7 @@ bool sdcard_poll(void)
|
|||
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;
|
||||
sdcard_endWriteBlocks();
|
||||
} else {
|
||||
sdcard.state = SDCARD_STATE_READY;
|
||||
}
|
||||
|
@ -424,7 +456,7 @@ bool sdcard_poll(void)
|
|||
}
|
||||
break;
|
||||
case SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE:
|
||||
if (SD_GetStatus() == SD_TRANSFER_OK) {
|
||||
if (SD_GetState()) {
|
||||
sdcard.state = SDCARD_STATE_READY;
|
||||
|
||||
#ifdef SDCARD_PROFILING
|
||||
|
@ -500,7 +532,8 @@ sdcardOperationStatus_e sdcard_writeBlock(uint32_t blockIndex, uint8_t *buffer,
|
|||
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) {
|
||||
//TODO: make sure buffer is aligned
|
||||
if (SD_WriteBlocks_DMA(blockIndex, (uint32_t*) buffer, 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.
|
||||
*/
|
||||
|
@ -544,16 +577,10 @@ sdcardOperationStatus_e sdcard_beginWriteBlocks(uint32_t blockIndex, uint32_t bl
|
|||
}
|
||||
}
|
||||
|
||||
// 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;
|
||||
// }
|
||||
sdcard.state = SDCARD_STATE_WRITING_MULTIPLE_BLOCKS;
|
||||
sdcard.multiWriteBlocksRemain = blockCount;
|
||||
sdcard.multiWriteNextBlock = blockIndex;
|
||||
return SDCARD_OPERATION_SUCCESS;
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -571,7 +598,13 @@ sdcardOperationStatus_e sdcard_beginWriteBlocks(uint32_t blockIndex, uint32_t bl
|
|||
bool sdcard_readBlock(uint32_t blockIndex, uint8_t *buffer, sdcard_operationCompleteCallback_c callback, uint32_t callbackData)
|
||||
{
|
||||
if (sdcard.state != SDCARD_STATE_READY) {
|
||||
return false;
|
||||
if (sdcard.state == SDCARD_STATE_WRITING_MULTIPLE_BLOCKS) {
|
||||
if (sdcard_endWriteBlocks() != SDCARD_OPERATION_SUCCESS) {
|
||||
return false;
|
||||
}
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef SDCARD_PROFILING
|
||||
|
@ -579,7 +612,7 @@ bool sdcard_readBlock(uint32_t blockIndex, uint8_t *buffer, sdcard_operationComp
|
|||
#endif
|
||||
|
||||
// Standard size cards use byte addressing, high capacity cards use block addressing
|
||||
uint8_t status = SD_ReadBlock(buffer, blockIndex * 512, 1);
|
||||
uint8_t status = SD_ReadBlocks_DMA(blockIndex, (uint32_t*) buffer, 512, 1);
|
||||
|
||||
if (status == SD_OK) {
|
||||
sdcard.pendingOperation.buffer = buffer;
|
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
|
@ -1,398 +0,0 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @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>© 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****/
|
|
@ -0,0 +1,228 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*
|
||||
* Original author: Alain (https://github.com/aroyer-qc)
|
||||
* Modified for F4 and BF source: Chris Hockuba (https://github.com/conkerkh)
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __fatfs_sd_sdio_H__
|
||||
#define __fatfs_sd_sdio_H__
|
||||
|
||||
#include <stdint.h>
|
||||
#include "stm32f4xx.h"
|
||||
|
||||
/* SDCARD pinouts
|
||||
*
|
||||
* SD CARD PINS
|
||||
_________________
|
||||
/ 1 2 3 4 5 6 7 8 | NR |SDIO INTERFACE
|
||||
/ | |NAME STM32F746 DESCRIPTION
|
||||
/ 9 | | 4-BIT 1-BIT
|
||||
| | |
|
||||
| | 1 |CD/DAT3 PC11 - Connector data line 3
|
||||
| | 2 |CMD PD2 PD2 Command/Response line
|
||||
| | 3 |VSS1 GND GND GND
|
||||
| SD CARD Pinout | 4 |VDD 3.3V 3.3V 3.3V Power supply
|
||||
| | 5 |CLK PC12 PC12 Clock
|
||||
| | 6 |VSS2 GND GND GND
|
||||
| | 7 |DAT0 PC8 PC8 Connector data line 0
|
||||
| | 8 |DAT1 PC9 - Connector data line 1
|
||||
|___________________| 9 |DAT2 PC10 - Connector data line 2
|
||||
|
||||
*/
|
||||
|
||||
/* Define(s) --------------------------------------------------------------------------------------------------------*/
|
||||
|
||||
//#define MSD_OK ((uint8_t)0x00)
|
||||
#define MSD_ERROR ((uint8_t)0x01)
|
||||
#define MSD_ERROR_SD_NOT_PRESENT ((uint8_t)0x02)
|
||||
|
||||
#define SD_PRESENT ((uint8_t)0x01)
|
||||
#define SD_NOT_PRESENT ((uint8_t)0x00)
|
||||
|
||||
#define SD_DATATIMEOUT ((uint32_t)100000000)
|
||||
|
||||
#define SD_DETECT_GPIO_PORT GPIOC
|
||||
#define SD_DETECT_PIN GPIO_PIN_13
|
||||
|
||||
/* Structure(s) -----------------------------------------------------------------------------------------------------*/
|
||||
|
||||
typedef enum
|
||||
{
|
||||
// SD specific error defines
|
||||
SD_CMD_CRC_FAIL = (1), // Command response received (but CRC check failed)
|
||||
SD_DATA_CRC_FAIL = (2), // Data block sent/received (CRC check failed)
|
||||
SD_CMD_RSP_TIMEOUT = (3), // Command response TimeOut
|
||||
SD_DATA_TIMEOUT = (4), // Data TimeOut
|
||||
SD_TX_UNDERRUN = (5), // Transmit FIFO underrun
|
||||
SD_RX_OVERRUN = (6), // Receive FIFO overrun
|
||||
SD_START_BIT_ERR = (7), // Start bit not detected on all data signals in wide bus mode
|
||||
SD_CMD_OUT_OF_RANGE = (8), // Command's argument was out of range.
|
||||
SD_ADDR_MISALIGNED = (9), // Misaligned address
|
||||
SD_BLOCK_LEN_ERR = (10), // Transferred block length is not allowed for the card or the number of transferred bytes does not match the block length
|
||||
SD_ERASE_SEQ_ERR = (11), // An error in the sequence of erase command occurs.
|
||||
SD_BAD_ERASE_PARAM = (12), // An invalid selection for erase groups
|
||||
SD_WRITE_PROT_VIOLATION = (13), // Attempt to program a write protect block
|
||||
SD_LOCK_UNLOCK_FAILED = (14), // Sequence or password error has been detected in unlock command or if there was an attempt to access a locked card
|
||||
SD_COM_CRC_FAILED = (15), // CRC check of the previous command failed
|
||||
SD_ILLEGAL_CMD = (16), // Command is not legal for the card state
|
||||
SD_CARD_ECC_FAILED = (17), // Card internal ECC was applied but failed to correct the data
|
||||
SD_CC_ERROR = (18), // Internal card controller error
|
||||
SD_GENERAL_UNKNOWN_ERROR = (19), // General or unknown error
|
||||
SD_STREAM_READ_UNDERRUN = (20), // The card could not sustain data transfer in stream read operation.
|
||||
SD_STREAM_WRITE_OVERRUN = (21), // The card could not sustain data programming in stream mode
|
||||
SD_CID_CSD_OVERWRITE = (22), // CID/CSD overwrite error
|
||||
SD_WP_ERASE_SKIP = (23), // Only partial address space was erased
|
||||
SD_CARD_ECC_DISABLED = (24), // Command has been executed without using internal ECC
|
||||
SD_ERASE_RESET = (25), // Erase sequence was cleared before executing because an out of erase sequence command was received
|
||||
SD_AKE_SEQ_ERROR = (26), // Error in sequence of authentication.
|
||||
SD_INVALID_VOLTRANGE = (27),
|
||||
SD_ADDR_OUT_OF_RANGE = (28),
|
||||
SD_SWITCH_ERROR = (29),
|
||||
SD_SDMMC_DISABLED = (30),
|
||||
SD_SDMMC_FUNCTION_BUSY = (31),
|
||||
SD_SDMMC_FUNCTION_FAILED = (32),
|
||||
SD_SDMMC_UNKNOWN_FUNCTION = (33),
|
||||
SD_OUT_OF_BOUND = (34),
|
||||
|
||||
|
||||
// Standard error defines
|
||||
SD_INTERNAL_ERROR = (35),
|
||||
SD_NOT_CONFIGURED = (36),
|
||||
SD_REQUEST_PENDING = (37),
|
||||
SD_REQUEST_NOT_APPLICABLE = (38),
|
||||
SD_INVALID_PARAMETER = (39),
|
||||
SD_UNSUPPORTED_FEATURE = (40),
|
||||
SD_UNSUPPORTED_HW = (41),
|
||||
SD_ERROR = (42),
|
||||
SD_BUSY = (43),
|
||||
SD_OK = (0)
|
||||
} SD_Error_t;
|
||||
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t DAT_BUS_WIDTH; // Shows the currently defined data bus width
|
||||
uint8_t SECURED_MODE; // Card is in secured mode of operation
|
||||
uint16_t SD_CARD_TYPE; // Carries information about card type
|
||||
uint32_t SIZE_OF_PROTECTED_AREA; // Carries information about the capacity of protected area
|
||||
uint8_t SPEED_CLASS; // Carries information about the speed class of the card
|
||||
uint8_t PERFORMANCE_MOVE; // Carries information about the card's performance move
|
||||
uint8_t AU_SIZE; // Carries information about the card's allocation unit size
|
||||
uint16_t ERASE_SIZE; // Determines the number of AUs to be erased in one operation
|
||||
uint8_t ERASE_TIMEOUT; // Determines the TimeOut for any number of AU erase
|
||||
uint8_t ERASE_OFFSET; // Carries information about the erase offset
|
||||
} SD_CardStatus_t;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t CSDStruct; // CSD structure
|
||||
uint8_t SysSpecVersion; // System specification version
|
||||
uint8_t Reserved1; // Reserved
|
||||
uint8_t TAAC; // Data read access time 1
|
||||
uint8_t NSAC; // Data read access time 2 in CLK cycles
|
||||
uint8_t MaxBusClkFrec; // Max. bus clock frequency
|
||||
uint16_t CardComdClasses; // Card command classes
|
||||
uint8_t RdBlockLen; // Max. read data block length
|
||||
uint8_t PartBlockRead; // Partial blocks for read allowed
|
||||
uint8_t WrBlockMisalign; // Write block misalignment
|
||||
uint8_t RdBlockMisalign; // Read block misalignment
|
||||
uint8_t DSRImpl; // DSR implemented
|
||||
uint8_t Reserved2; // Reserved
|
||||
uint32_t DeviceSize; // Device Size
|
||||
uint8_t MaxRdCurrentVDDMin; // Max. read current @ VDD min
|
||||
uint8_t MaxRdCurrentVDDMax; // Max. read current @ VDD max
|
||||
uint8_t MaxWrCurrentVDDMin; // Max. write current @ VDD min
|
||||
uint8_t MaxWrCurrentVDDMax; // Max. write current @ VDD max
|
||||
uint8_t DeviceSizeMul; // Device size multiplier
|
||||
uint8_t EraseGrSize; // Erase group size
|
||||
uint8_t EraseGrMul; // Erase group size multiplier
|
||||
uint8_t WrProtectGrSize; // Write protect group size
|
||||
uint8_t WrProtectGrEnable; // Write protect group enable
|
||||
uint8_t ManDeflECC; // Manufacturer default ECC
|
||||
uint8_t WrSpeedFact; // Write speed factor
|
||||
uint8_t MaxWrBlockLen; // Max. write data block length
|
||||
uint8_t WriteBlockPaPartial; // Partial blocks for write allowed
|
||||
uint8_t Reserved3; // Reserved
|
||||
uint8_t ContentProtectAppli; // Content protection application
|
||||
uint8_t FileFormatGrouop; // File format group
|
||||
uint8_t CopyFlag; // Copy flag (OTP)
|
||||
uint8_t PermWrProtect; // Permanent write protection
|
||||
uint8_t TempWrProtect; // Temporary write protection
|
||||
uint8_t FileFormat; // File format
|
||||
uint8_t ECC; // ECC code
|
||||
uint8_t CSD_CRC; // CSD CRC
|
||||
uint8_t Reserved4; // Always 1
|
||||
} SD_CSD_t;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t ManufacturerID; // Manufacturer ID
|
||||
uint16_t OEM_AppliID; // OEM/Application ID
|
||||
uint32_t ProdName1; // Product Name part1
|
||||
uint8_t ProdName2; // Product Name part2
|
||||
uint8_t ProdRev; // Product Revision
|
||||
uint32_t ProdSN; // Product Serial Number
|
||||
uint8_t Reserved1; // Reserved1
|
||||
uint16_t ManufactDate; // Manufacturing Date
|
||||
uint8_t CID_CRC; // CID CRC
|
||||
uint8_t Reserved2; // Always 1
|
||||
|
||||
} SD_CID_t;
|
||||
|
||||
typedef enum
|
||||
{
|
||||
SD_STD_CAPACITY_V1_1 = 0,
|
||||
SD_STD_CAPACITY_V2_0 = 1,
|
||||
SD_HIGH_CAPACITY = 2,
|
||||
SD_MULTIMEDIA = 3,
|
||||
SD_SECURE_DIGITAL_IO = 4,
|
||||
SD_HIGH_SPEED_MULTIMEDIA = 5,
|
||||
SD_SECURE_DIGITAL_IO_COMBO = 6,
|
||||
SD_HIGH_CAPACITY_MMC = 7,
|
||||
} SD_CardType_t;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
volatile SD_CSD_t SD_csd; // SD card specific data register
|
||||
volatile SD_CID_t SD_cid; // SD card identification number register
|
||||
uint64_t CardCapacity; // Card capacity
|
||||
uint32_t CardBlockSize; // Card block size
|
||||
} SD_CardInfo_t;
|
||||
|
||||
/* Prototype(s) -----------------------------------------------------------------------------------------------------*/
|
||||
|
||||
extern SD_CardInfo_t SD_CardInfo;
|
||||
extern SD_CardType_t SD_CardType;
|
||||
|
||||
void SD_Initialize_LL (DMA_Stream_TypeDef *dma);
|
||||
bool SD_Init (void);
|
||||
bool SD_IsDetected (void);
|
||||
bool SD_GetState (void);
|
||||
SD_Error_t SD_GetCardInfo (void);
|
||||
|
||||
SD_Error_t SD_ReadBlocks_DMA (uint64_t ReadAddress, uint32_t *buffer, uint32_t BlockSize, uint32_t NumberOfBlocks);
|
||||
SD_Error_t SD_CheckRead (void);
|
||||
SD_Error_t SD_WriteBlocks_DMA (uint64_t WriteAddress, uint32_t *buffer, uint32_t BlockSize, uint32_t NumberOfBlocks);
|
||||
SD_Error_t SD_CheckWrite (void);
|
||||
|
||||
SD_Error_t SD_Erase (uint64_t StartAddress, uint64_t EndAddress);
|
||||
SD_Error_t SD_GetCardStatus (SD_CardStatus_t* pCardStatus);
|
||||
|
||||
/* ------------------------------------------------------------------------------------------------------------------*/
|
||||
|
||||
#endif // __fatfs_sd_sdio_H__
|
|
@ -38,6 +38,8 @@ void pgResetFn_sdcardConfig(sdcardConfig_t *config)
|
|||
#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;
|
||||
|
@ -63,6 +65,9 @@ void pgResetFn_sdcardConfig(sdcardConfig_t *config)
|
|||
config->dmaIdentifier = (uint8_t)dmaGetIdentifier(SDCARD_DMA_STREAM_TX_FULL);
|
||||
#elif defined(SDCARD_DMA_CHANNEL_TX)
|
||||
config->dmaIdentifier = (uint8_t)dmaGetIdentifier(SDCARD_DMA_CHANNEL_TX);
|
||||
#elif defined(SDIO_DMA)
|
||||
config->dmaIdentifier = (uint8_t)dmaGetIdentifier(SDIO_DMA);
|
||||
config->useDma = true;
|
||||
#endif
|
||||
|
||||
#if (defined(STM32F4) || defined(STM32F7)) && defined(SDCARD_DMA_CHANNEL)
|
||||
|
|
|
@ -26,13 +26,12 @@
|
|||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
|
||||
DEF_TIM(TIM4, CH4, PB9, TIM_USE_PPM | TIM_USE_PWM, 1, 0 ), // PPM IN
|
||||
DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR, 0, 1 ), // S1_OUT - DMA1_ST1_CH3
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 1 ), // S2_OUT - DMA1_ST2_CH5
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 0, 0 ), // S3_OUT - DMA1_ST6_CH3
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0, 1 ), // S4_OUT - DMA1_ST7_CH5
|
||||
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_LED, 0, 0 ), // LED_STRIP - DMA1_ST2_CH5
|
||||
|
||||
DEF_TIM(TIM4, CH4, PB9, TIM_USE_PPM, 1, 0 ), // PPM IN
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0 ), // S1_OUT - TIM3_UP - BURST
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0 ), // S2_OUT - TIM3_UP - BURST
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 0, 0 ), // S3_OUT - TIM2_UP - BURST
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0, 1 ), // S4_OUT - TIM2_UP - BURST
|
||||
DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_LED, 0, 1 ), // S5_OUT - TIM1_UP - BURST
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 1 ), // S6_OUT - TIM1_UP - BURST
|
||||
};
|
||||
|
||||
|
|
|
@ -24,6 +24,9 @@
|
|||
#define LED0_PIN PA15
|
||||
#define LED1_PIN PC14
|
||||
|
||||
#define USE_DSHOT_DMAR
|
||||
#define ENABLE_DSHOT_DMAR true
|
||||
|
||||
//BEEPER
|
||||
#define USE_BEEPER
|
||||
#define BEEPER_PIN PB14
|
||||
|
@ -63,6 +66,8 @@
|
|||
#define INVERTER_PIN_UART3 PB12
|
||||
|
||||
#define USE_VCP
|
||||
#define USB_MSC
|
||||
#define MSC_BUTTON PB2
|
||||
#define VBUS_SENSING_PIN PA9
|
||||
#define VBUS_SENSING_ENABLED
|
||||
|
||||
|
@ -74,11 +79,15 @@
|
|||
#define UART3_RX_PIN PB11
|
||||
#define UART3_TX_PIN PB10
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_RX_PIN PA1
|
||||
#define UART4_TX_PIN PA0
|
||||
|
||||
#define USE_UART6
|
||||
#define UART6_RX_PIN PC7
|
||||
#define UART6_TX_PIN PC6
|
||||
|
||||
#define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6
|
||||
#define SERIAL_PORT_COUNT 5 //VCP, USART1, USART3, USART4, USART6
|
||||
|
||||
#define USE_ESCSERIAL
|
||||
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
|
||||
|
@ -117,7 +126,7 @@
|
|||
//SD CARD
|
||||
#define USE_SDCARD
|
||||
#define USE_SDCARD_SDIO
|
||||
#define SDIO_DMA
|
||||
#define SDIO_DMA DMA2_Stream3
|
||||
#define SDCARD_SPI_CS_PIN NONE //This is not used on SDIO, has to be kept for now to keep compiler happy
|
||||
#define SDCARD_DETECT_PIN PB15
|
||||
|
||||
|
@ -126,5 +135,5 @@
|
|||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(2))
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 6
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 7
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8))
|
||||
|
|
|
@ -11,8 +11,8 @@ TARGET_SRC = \
|
|||
|
||||
|
||||
TARGET_SRC += \
|
||||
drivers/sdio_stdlib.c \
|
||||
drivers/sdcard_sdio_stdlib.c \
|
||||
drivers/sdio_f4xx.c \
|
||||
drivers/sdcard_sdio_baremetal.c \
|
||||
drivers/sdcard_standard.c \
|
||||
io/asyncfatfs/asyncfatfs.c \
|
||||
io/asyncfatfs/fat_standard.c
|
Loading…
Reference in New Issue