1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-22 07:45:29 +03:00

Cache up SDIO Writing, add option to enable clock bypass. (#5612)

* Speed up SDIO Writing, add option to enable clock bypass.

* Fix identation

* Requested changes

* Move PG SDIO into correct place.
This commit is contained in:
Chris 2018-04-05 02:52:30 +02:00 committed by Michael Keller
parent 21e77dd66d
commit c71cfe1b8c
7 changed files with 142 additions and 11 deletions

View file

@ -396,6 +396,7 @@ SRC += \
drivers/sdcard_standard.c \ drivers/sdcard_standard.c \
io/asyncfatfs/asyncfatfs.c \ io/asyncfatfs/asyncfatfs.c \
io/asyncfatfs/fat_standard.c \ io/asyncfatfs/fat_standard.c \
pg/sdio.c \
$(MSC_SRC) $(MSC_SRC)
endif endif

View file

@ -38,6 +38,9 @@
#include "drivers/sdmmc_sdio.h" #include "drivers/sdmmc_sdio.h"
#include "pg/pg.h"
#include "pg/sdio.h"
#ifdef AFATFS_USE_INTROSPECTIVE_LOGGING #ifdef AFATFS_USE_INTROSPECTIVE_LOGGING
#define SDCARD_PROFILING #define SDCARD_PROFILING
#endif #endif
@ -45,6 +48,31 @@
#define SDCARD_TIMEOUT_INIT_MILLIS 200 #define SDCARD_TIMEOUT_INIT_MILLIS 200
#define SDCARD_MAX_CONSECUTIVE_FAILURES 8 #define SDCARD_MAX_CONSECUTIVE_FAILURES 8
// Use this to speed up writing to SDCARD... asyncfatfs has limited support for multiblock write
#define FATFS_BLOCK_CACHE_SIZE 16
uint8_t writeCache[512 * FATFS_BLOCK_CACHE_SIZE] __attribute__ ((aligned (4)));
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;
}
typedef enum { typedef enum {
// In these states we run at the initialization 400kHz clockspeed: // In these states we run at the initialization 400kHz clockspeed:
SDCARD_STATE_NOT_PRESENT = 0, SDCARD_STATE_NOT_PRESENT = 0,
@ -97,6 +125,7 @@ typedef struct sdcard_t {
IO_t cardDetectPin; IO_t cardDetectPin;
dmaIdentifier_e dma; dmaIdentifier_e dma;
uint8_t dmaChannel; uint8_t dmaChannel;
uint8_t useCache;
} sdcard_t; } sdcard_t;
static sdcard_t sdcard; static sdcard_t sdcard;
@ -267,6 +296,11 @@ void sdcard_init(const sdcardConfig_t *config)
} else { } else {
sdcard.cardDetectPin = IO_NONE; sdcard.cardDetectPin = IO_NONE;
} }
if (sdioConfig()->useCache) {
sdcard.useCache = 1;
} else {
sdcard.useCache = 0;
}
SD_Initialize_LL(dmaGetRefByIdentifier(sdcard.dma)); SD_Initialize_LL(dmaGetRefByIdentifier(sdcard.dma));
if (SD_IsDetected()) { if (SD_IsDetected()) {
if (SD_Init() != 0) { if (SD_Init() != 0) {
@ -306,6 +340,9 @@ static bool sdcard_isReady()
static sdcardOperationStatus_e sdcard_endWriteBlocks() static sdcardOperationStatus_e sdcard_endWriteBlocks()
{ {
sdcard.multiWriteBlocksRemain = 0; sdcard.multiWriteBlocksRemain = 0;
if (sdcard.useCache) {
cache_reset();
}
// 8 dummy clocks to guarantee N_WR clocks between the last card response and this token // 8 dummy clocks to guarantee N_WR clocks between the last card response and this token
@ -399,6 +436,9 @@ bool sdcard_poll(void)
if (sdcard.multiWriteBlocksRemain > 1) { if (sdcard.multiWriteBlocksRemain > 1) {
sdcard.multiWriteBlocksRemain--; sdcard.multiWriteBlocksRemain--;
sdcard.multiWriteNextBlock++; sdcard.multiWriteNextBlock++;
if (sdcard.useCache) {
cache_reset();
}
sdcard.state = SDCARD_STATE_WRITING_MULTIPLE_BLOCKS; sdcard.state = SDCARD_STATE_WRITING_MULTIPLE_BLOCKS;
} else if (sdcard.multiWriteBlocksRemain == 1) { } else if (sdcard.multiWriteBlocksRemain == 1) {
// This function changes the sd card state for us whether immediately succesful or delayed: // This function changes the sd card state for us whether immediately succesful or delayed:
@ -527,13 +567,31 @@ sdcardOperationStatus_e sdcard_writeBlock(uint32_t blockIndex, uint8_t *buffer,
sdcard.pendingOperation.buffer = buffer; sdcard.pendingOperation.buffer = buffer;
sdcard.pendingOperation.blockIndex = blockIndex; sdcard.pendingOperation.blockIndex = blockIndex;
uint16_t block_count = 1;
if ((cache_getCount() < FATFS_BLOCK_CACHE_SIZE) &&
(sdcard.multiWriteBlocksRemain != 0) && sdcard.useCache) {
cache_write(buffer);
if (cache_getCount() == FATFS_BLOCK_CACHE_SIZE || sdcard.multiWriteBlocksRemain == 1) {
//Relocate buffer
buffer = (uint8_t*)writeCache;
//Recalculate block index
blockIndex -= cache_getCount() - 1;
block_count = cache_getCount();
} else {
sdcard.multiWriteBlocksRemain--;
sdcard.multiWriteNextBlock++;
sdcard.state = SDCARD_STATE_READY;
return SDCARD_OPERATION_SUCCESS;
}
}
sdcard.pendingOperation.callback = callback; sdcard.pendingOperation.callback = callback;
sdcard.pendingOperation.callbackData = callbackData; sdcard.pendingOperation.callbackData = callbackData;
sdcard.pendingOperation.chunkIndex = 1; // (for non-DMA transfers) we've sent chunk #0 already sdcard.pendingOperation.chunkIndex = 1; // (for non-DMA transfers) we've sent chunk #0 already
sdcard.state = SDCARD_STATE_SENDING_WRITE; sdcard.state = SDCARD_STATE_SENDING_WRITE;
//TODO: make sure buffer is aligned if (SD_WriteBlocks_DMA(blockIndex, (uint32_t*) buffer, 512, block_count) != SD_OK) {
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 /* 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. * the card is broken and needs reset.
*/ */

View file

@ -32,6 +32,9 @@
#include "platform.h" #include "platform.h"
#include "stm32f4xx_gpio.h" #include "stm32f4xx_gpio.h"
#include "pg/pg.h"
#include "pg/sdio.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/io_impl.h" #include "drivers/io_impl.h"
#include "drivers/nvic.h" #include "drivers/nvic.h"
@ -1122,8 +1125,7 @@ static SD_Error_t SD_WideBusOperationConfig(uint32_t WideMode)
* This API must be used after "Transfer State" * This API must be used after "Transfer State"
* @retval SD Card error state * @retval SD Card error state
*/ */
/* SD_Error_t SD_HighSpeed(void)
SD_Error_t HAL_SD_HighSpeed(void)
{ {
SD_Error_t ErrorState; SD_Error_t ErrorState;
uint8_t SD_hs[64] = {0}; uint8_t SD_hs[64] = {0};
@ -1147,16 +1149,16 @@ SD_Error_t HAL_SD_HighSpeed(void)
if(SD_SPEC != SD_ALLZERO) if(SD_SPEC != SD_ALLZERO)
{ {
// Set Block Size for Card // Set Block Size for Card
if((ErrorState = SD_TransmitCommand((SD_CMD_SET_BLOCKLEN | SDIO_CMD_RESPONSE_SHORT), 64, 1)) != SD_OK) if((ErrorState = SD_TransmitCommand((SD_CMD_SET_BLOCKLEN | SD_CMD_RESPONSE_SHORT), 64, 1)) != SD_OK)
{ {
return ErrorState; return ErrorState;
} }
// Configure the SD DPSM (Data Path State Machine) // Configure the SD DPSM (Data Path State Machine)
SD_DataTransferInit(64, SDIO_DATABLOCK_SIZE_64B, true); SD_DataTransferInit(64, SD_DATABLOCK_SIZE_64B, true);
// Send CMD6 switch mode // Send CMD6 switch mode
if((ErrorState =SD_TransmitCommand((SD_CMD_HS_SWITCH | SDIO_CMD_RESPONSE_SHORT), 0x80FFFF01, 1)) != SD_OK) if((ErrorState =SD_TransmitCommand((SD_CMD_HS_SWITCH | SD_CMD_RESPONSE_SHORT), 0x80FFFF01, 1)) != SD_OK)
{ {
return ErrorState; return ErrorState;
} }
@ -1197,8 +1199,6 @@ SD_Error_t HAL_SD_HighSpeed(void)
return ErrorState; return ErrorState;
} }
*/
/** -----------------------------------------------------------------------------------------------------------------*/ /** -----------------------------------------------------------------------------------------------------------------*/
/** /**
@ -1673,6 +1673,13 @@ bool SD_Init(void)
{ {
// Enable wide operation // Enable wide operation
ErrorState = SD_WideBusOperationConfig(SD_BUS_WIDE_4B); ErrorState = SD_WideBusOperationConfig(SD_BUS_WIDE_4B);
if (ErrorState == SD_OK && sdioConfig()->clockBypass) {
if (SD_HighSpeed()) {
SDIO->CLKCR |= SDIO_CLKCR_BYPASS;
SDIO->CLKCR |= SDIO_CLKCR_NEGEDGE;
}
}
} }
// Configure the SDCARD device // Configure the SDCARD device

View file

@ -75,6 +75,7 @@
#include "pg/sdcard.h" #include "pg/sdcard.h"
#include "pg/vcd.h" #include "pg/vcd.h"
#include "pg/usb.h" #include "pg/usb.h"
#include "pg/sdio.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "rx/cc2500_frsky_common.h" #include "rx/cc2500_frsky_common.h"
@ -718,7 +719,7 @@ const clivalue_t valueTable[] = {
{ "throttle_boost", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 100 }, PG_PID_PROFILE, offsetof(pidProfile_t, throttle_boost) }, { "throttle_boost", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 100 }, PG_PID_PROFILE, offsetof(pidProfile_t, throttle_boost) },
{ "throttle_boost_cutoff", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 5, 50 }, PG_PID_PROFILE, offsetof(pidProfile_t, throttle_boost_cutoff) }, { "throttle_boost_cutoff", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 5, 50 }, PG_PID_PROFILE, offsetof(pidProfile_t, throttle_boost_cutoff) },
{ "p_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_PITCH].P) }, { "p_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_PITCH].P) },
{ "i_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_PITCH].I) }, { "i_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_PITCH].I) },
{ "d_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_PITCH].D) }, { "d_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_PITCH].D) },
@ -790,6 +791,10 @@ const clivalue_t valueTable[] = {
#ifdef USE_SDCARD #ifdef USE_SDCARD
{ "sdcard_dma", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SDCARD_CONFIG, offsetof(sdcardConfig_t, useDma) }, { "sdcard_dma", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SDCARD_CONFIG, offsetof(sdcardConfig_t, useDma) },
#endif #endif
#ifdef USE_SDCARD_SDIO
{ "sdio_clk_bypass", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SDIO_CONFIG, offsetof(sdioConfig_t, clockBypass) },
{ "sdio_use_cache", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SDIO_CONFIG, offsetof(sdioConfig_t, useCache) },
#endif
// PG_OSD_CONFIG // PG_OSD_CONFIG
#ifdef USE_OSD #ifdef USE_OSD

View file

@ -122,7 +122,8 @@
#define PG_PINIO_CONFIG 529 #define PG_PINIO_CONFIG 529
#define PG_PINIOBOX_CONFIG 530 #define PG_PINIOBOX_CONFIG 530
#define PG_USB_CONFIG 531 #define PG_USB_CONFIG 531
#define PG_BETAFLIGHT_END 531 #define PG_SDIO_CONFIG 532
#define PG_BETAFLIGHT_END 532
// OSD configuration (subject to change) // OSD configuration (subject to change)

32
src/main/pg/sdio.c Normal file
View file

@ -0,0 +1,32 @@
/*
* 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 "platform.h"
#if defined(USE_SDCARD_SDIO)
#include "pg/pg_ids.h"
#include "pg/sdio.h"
PG_REGISTER_WITH_RESET_TEMPLATE(sdioConfig_t, sdioConfig, PG_SDIO_CONFIG, 0);
PG_RESET_TEMPLATE(sdioConfig_t, sdioConfig,
.clockBypass = 0,
.useCache = 0,
);
#endif

27
src/main/pg/sdio.h Normal file
View file

@ -0,0 +1,27 @@
/*
* 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/>.
*/
#pragma once
#include "pg/pg.h"
typedef struct sdioConfig_s {
uint8_t clockBypass;
uint8_t useCache;
} sdioConfig_t;
PG_DECLARE(sdioConfig_t, sdioConfig);