Prepare SD card SPI and SDIO variants for consolidation

This commit is contained in:
jflyper 2018-09-27 23:42:06 +09:00
parent 8980ba1065
commit 00840ce40f
109 changed files with 1397 additions and 1262 deletions

View File

@ -43,7 +43,14 @@ DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC)\
$(USBPERIPH_SRC)
endif
ifneq ($(filter SDCARD, $(FEATURES)),)
ifneq ($(filter SDCARD_SPI, $(FEATURES)),)
INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(FATFS_DIR) \
VPATH := $(VPATH):$(FATFS_DIR)
endif
ifneq ($(filter SDCARD_SDIO, $(FEATURES)),)
INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(FATFS_DIR) \

View File

@ -137,7 +137,13 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(ROOT)/src/main/vcpf4
endif
ifneq ($(filter SDCARD,$(FEATURES)),)
ifneq ($(filter SDCARD_SPI,$(FEATURES)),)
INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(FATFS_DIR)
VPATH := $(VPATH):$(FATFS_DIR)
endif
ifneq ($(filter SDCARD_SDIO,$(FEATURES)),)
INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(FATFS_DIR)
VPATH := $(VPATH):$(FATFS_DIR)
@ -202,12 +208,12 @@ MSC_SRC = \
msc/usbd_msc_desc.c \
msc/usbd_storage.c
ifneq ($(filter SDCARD,$(FEATURES)),)
ifneq ($(filter SDCARD_SPI,$(FEATURES)),)
MSC_SRC += \
msc/usbd_storage_sd_spi.c
endif
ifneq ($(filter SDIO,$(FEATURES)),)
ifneq ($(filter SDCARD_SDIO,$(FEATURES)),)
MSC_SRC += \
msc/usbd_storage_sdio.c
MCU_COMMON_SRC += \

View File

@ -117,7 +117,13 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(ROOT)/lib/main/STM32F7/Drivers/CMSIS/Device/ST/STM32F7xx/Include \
$(ROOT)/src/main/vcp_hal
ifneq ($(filter SDCARD,$(FEATURES)),)
ifneq ($(filter SDCARD_SPI,$(FEATURES)),)
INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(FATFS_DIR)
VPATH := $(VPATH):$(FATFS_DIR)
endif
ifneq ($(filter SDCARD_SDIO,$(FEATURES)),)
INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(FATFS_DIR)
VPATH := $(VPATH):$(FATFS_DIR)
@ -189,14 +195,14 @@ MSC_SRC = \
drivers/usb_msc_f7xx.c \
msc/usbd_storage.c
ifneq ($(filter SDIO,$(FEATURES)),)
ifneq ($(filter SDCARD_SDIO,$(FEATURES)),)
MCU_COMMON_SRC += \
drivers/sdio_f7xx.c
MSC_SRC += \
msc/usbd_storage_sdio.c
endif
ifneq ($(filter SDCARD,$(FEATURES)),)
ifneq ($(filter SDCARD_SPI,$(FEATURES)),)
MSC_SRC += \
msc/usbd_storage_sd_spi.c
endif

View File

@ -355,17 +355,19 @@ SRC += $(COMMON_SRC)
#excludes
SRC := $(filter-out $(MCU_EXCLUDES), $(SRC))
ifneq ($(filter SDCARD,$(FEATURES)),)
ifneq ($(filter SDCARD_SPI,$(FEATURES)),)
SRC += \
drivers/sdcard.c \
drivers/sdcard_spi.c \
drivers/sdcard_standard.c \
io/asyncfatfs/asyncfatfs.c \
io/asyncfatfs/fat_standard.c \
$(MSC_SRC)
endif
ifneq ($(filter SDIO,$(FEATURES)),)
ifneq ($(filter SDCARD_SDIO,$(FEATURES)),)
SRC += \
drivers/sdcard.c \
drivers/sdcard_sdio_baremetal.c \
drivers/sdcard_standard.c \
io/asyncfatfs/asyncfatfs.c \

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,113 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "drivers/nvic.h"
#include "drivers/io.h"
#include "dma.h"
#include "drivers/bus_spi.h"
#include "drivers/time.h"
#include "sdcard.h"
#include "sdcard_standard.h"
#ifdef AFATFS_USE_INTROSPECTIVE_LOGGING
#define SDCARD_PROFILING
#endif
#define SDCARD_TIMEOUT_INIT_MILLIS 200
#define SDCARD_MAX_CONSECUTIVE_FAILURES 8
typedef enum {
// In these states we run at the initialization 400kHz clockspeed:
SDCARD_STATE_NOT_PRESENT = 0,
SDCARD_STATE_RESET,
SDCARD_STATE_CARD_INIT_IN_PROGRESS,
SDCARD_STATE_INITIALIZATION_RECEIVE_CID,
// In these states we run at full clock speed
SDCARD_STATE_READY,
SDCARD_STATE_READING,
SDCARD_STATE_SENDING_WRITE,
SDCARD_STATE_WAITING_FOR_WRITE,
SDCARD_STATE_WRITING_MULTIPLE_BLOCKS,
SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE
} sdcardState_e;
typedef struct sdcard_t {
struct {
uint8_t *buffer;
uint32_t blockIndex;
uint8_t chunkIndex;
sdcard_operationCompleteCallback_c callback;
uint32_t callbackData;
#ifdef SDCARD_PROFILING
uint32_t profileStartTime;
#endif
} pendingOperation;
uint32_t operationStartTime;
uint8_t failureCount;
uint8_t version;
bool highCapacity;
uint32_t multiWriteNextBlock;
uint32_t multiWriteBlocksRemain;
sdcardState_e state;
sdcardMetadata_t metadata;
sdcardCSD_t csd;
#ifdef SDCARD_PROFILING
sdcard_profilerCallback_c profiler;
#endif
bool enabled;
bool detectionInverted;
IO_t cardDetectPin;
#ifdef USE_SDCARD_SPI
SPI_TypeDef *instance;
IO_t chipSelectPin;
bool useDMAForTx;
dmaChannelDescriptor_t * dma;
#endif
#ifdef USE_SDCARD_SDIO
dmaIdentifier_e dmaIdentifier;
uint8_t useCache;
#endif
uint8_t dmaChannel;
} sdcard_t;
extern sdcard_t sdcard;
STATIC_ASSERT(sizeof(sdcardCSD_t) == 16, sdcard_csd_bitfields_didnt_pack_properly);
void sdcardInsertionDetectInit(void);
void sdcardInsertionDetectDeinit(void);
bool sdcard_isInserted(void);

View File

@ -26,7 +26,6 @@
#include "platform.h"
#define USE_SDCARD_SDIO
#ifdef USE_SDCARD_SDIO
#include "drivers/nvic.h"
@ -36,6 +35,7 @@
#include "drivers/time.h"
#include "drivers/sdcard.h"
#include "drivers/sdcard_impl.h"
#include "drivers/sdcard_standard.h"
#include "drivers/sdmmc_sdio.h"
@ -43,13 +43,6 @@
#include "pg/pg.h"
#include "pg/sdio.h"
#ifdef AFATFS_USE_INTROSPECTIVE_LOGGING
#define SDCARD_PROFILING
#endif
#define SDCARD_TIMEOUT_INIT_MILLIS 200
#define SDCARD_MAX_CONSECUTIVE_FAILURES 8
// Use this to speed up writing to SDCARD... asyncfatfs has limited support for multiblock write
#define FATFS_BLOCK_CACHE_SIZE 16
uint8_t writeCache[512 * FATFS_BLOCK_CACHE_SIZE] __attribute__ ((aligned (4)));
@ -75,93 +68,6 @@ void cache_reset(void)
cacheCount = 0;
}
typedef enum {
// In these states we run at the initialization 400kHz clockspeed:
SDCARD_STATE_NOT_PRESENT = 0,
SDCARD_STATE_RESET,
SDCARD_STATE_CARD_INIT_IN_PROGRESS,
SDCARD_STATE_INITIALIZATION_RECEIVE_CID,
// In these states we run at full clock speed
SDCARD_STATE_READY,
SDCARD_STATE_READING,
SDCARD_STATE_SENDING_WRITE,
SDCARD_STATE_WAITING_FOR_WRITE,
SDCARD_STATE_WRITING_MULTIPLE_BLOCKS,
SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE
} sdcardState_e;
typedef struct sdcard_t {
struct {
uint8_t *buffer;
uint32_t blockIndex;
uint8_t chunkIndex;
sdcard_operationCompleteCallback_c callback;
uint32_t callbackData;
#ifdef SDCARD_PROFILING
uint32_t profileStartTime;
#endif
} pendingOperation;
uint32_t operationStartTime;
uint8_t failureCount;
uint8_t version;
bool highCapacity;
uint32_t multiWriteNextBlock;
uint32_t multiWriteBlocksRemain;
sdcardState_e state;
sdcardMetadata_t metadata;
sdcardCSD_t csd;
#ifdef SDCARD_PROFILING
sdcard_profilerCallback_c profiler;
#endif
bool enabled;
IO_t cardDetectPin;
dmaIdentifier_e dma;
uint8_t dmaChannel;
uint8_t useCache;
} sdcard_t;
static sdcard_t sdcard;
STATIC_ASSERT(sizeof(sdcardCSD_t) == 16, sdcard_csd_bitfields_didnt_pack_properly);
void sdcardInsertionDetectDeinit(void)
{
if (sdcard.cardDetectPin) {
IOInit(sdcard.cardDetectPin, OWNER_FREE, 0);
IOConfigGPIO(sdcard.cardDetectPin, IOCFG_IN_FLOATING);
}
}
void sdcardInsertionDetectInit(void)
{
if (sdcard.cardDetectPin) {
IOInit(sdcard.cardDetectPin, OWNER_SDCARD_DETECT, 0);
IOConfigGPIO(sdcard.cardDetectPin, IOCFG_IPU);
}
}
/**
* Detect if a SD card is physically present in the memory slot.
*/
bool sdcard_isInserted(void)
{
bool ret = true;
if (sdcard.cardDetectPin) {
ret = IORead(sdcard.cardDetectPin) == 0;
}
return ret;
}
/**
* Returns true if the card has already been, or is currently, initializing and hasn't encountered enough errors to
* trip our error threshold and be disabled (i.e. our card is in and working!)
@ -288,8 +194,8 @@ void sdcard_init(const sdcardConfig_t *config)
sdcard.state = SDCARD_STATE_NOT_PRESENT;
return;
}
sdcard.dma = config->dmaIdentifier;
if (sdcard.dma == 0) {
sdcard.dmaIdentifier = config->dmaIdentifier;
if (sdcard.dmaIdentifier == 0) {
sdcard.state = SDCARD_STATE_NOT_PRESENT;
return;
}
@ -303,7 +209,7 @@ void sdcard_init(const sdcardConfig_t *config)
} else {
sdcard.useCache = 0;
}
SD_Initialize_LL(dmaGetRefByIdentifier(sdcard.dma));
SD_Initialize_LL(dmaGetRefByIdentifier(sdcard.dmaIdentifier));
if (SD_IsDetected()) {
if (SD_Init() != 0) {
sdcard.state = SDCARD_STATE_NOT_PRESENT;

File diff suppressed because it is too large Load Diff

View File

@ -31,9 +31,11 @@
#include "stdbool.h"
#include <string.h>
#include "sdmmc_sdio.h"
#include "platform.h"
#ifdef USE_SDCARD_SDIO
#include "sdmmc_sdio.h"
#include "stm32f4xx_gpio.h"
#include "pg/pg.h"
@ -1899,3 +1901,4 @@ void SDIO_DMA_ST6_IRQHandler(dmaChannelDescriptor_t *dma)
}
/* ------------------------------------------------------------------------------------------------------------------*/
#endif

View File

@ -28,9 +28,11 @@
#include "stdbool.h"
#include <string.h>
#include "sdmmc_sdio.h"
#include "platform.h"
#ifdef USE_SDCARD_SDIO
#include "sdmmc_sdio.h"
#include "stm32f7xx.h"
#include "drivers/io.h"
@ -1899,3 +1901,4 @@ void SDMMC_DMA_ST6_IRQHandler(dmaChannelDescriptor_t *dma)
}
/* ------------------------------------------------------------------------------------------------------------------*/
#endif

View File

@ -3816,7 +3816,7 @@ const cliResourceValue_t resourceTable[] = {
DEFS( OWNER_COMPASS_EXTI, PG_COMPASS_CONFIG, compassConfig_t, interruptTag ),
#endif
#endif
#ifdef USE_SDCARD
#ifdef USE_SDCARD_SPI
DEFS( OWNER_SDCARD_CS, PG_SDCARD_CONFIG, sdcardConfig_t, chipSelectTag ),
DEFS( OWNER_SDCARD_DETECT, PG_SDCARD_CONFIG, sdcardConfig_t, cardDetectTag ),
#endif

View File

@ -393,6 +393,12 @@ static const char * const lookupTableVtxLowPowerDisarm[] = {
};
#endif
#ifdef USE_SDCARD
static const char * const lookupTableSdcardMode[] = {
"OFF", "SPI", "SDIO"
};
#endif
#define LOOKUP_TABLE_ENTRY(name) { name, ARRAYLEN(name) }
const lookupTableEntry_t lookupTables[] = {
@ -490,6 +496,9 @@ const lookupTableEntry_t lookupTables[] = {
LOOKUP_TABLE_ENTRY(lookupTableVtxLowPowerDisarm),
#endif
LOOKUP_TABLE_ENTRY(lookupTableGyroHardware),
#ifdef USE_SDCARD
LOOKUP_TABLE_ENTRY(lookupTableSdcardMode),
#endif
};
#undef LOOKUP_TABLE_ENTRY
@ -933,7 +942,12 @@ const clivalue_t valueTable[] = {
// PG_SDCARD_CONFIG
#ifdef USE_SDCARD
{ "sdcard_detect_inverted", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SDCARD_CONFIG, offsetof(sdcardConfig_t, cardDetectInverted) },
{ "sdcard_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SDCARD_MODE }, PG_SDCARD_CONFIG, offsetof(sdcardConfig_t, mode) },
#endif
#ifdef USE_SDCARD_SPI
{ "sdcard_dma", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SDCARD_CONFIG, offsetof(sdcardConfig_t, useDma) },
{ "sdcard_spi_bus", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, SPIDEV_COUNT }, PG_SDCARD_CONFIG, offsetof(sdcardConfig_t, device) },
#endif
#ifdef USE_SDCARD_SDIO
{ "sdio_clk_bypass", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SDIO_CONFIG, offsetof(sdioConfig_t, clockBypass) },

View File

@ -120,6 +120,9 @@ typedef enum {
TABLE_VTX_LOW_POWER_DISARM,
#endif
TABLE_GYRO_HARDWARE,
#ifdef USE_SDCARD
TABLE_SDCARD_MODE,
#endif
LOOKUP_TABLE_COUNT
} lookupTableIndex_e;

View File

@ -38,32 +38,32 @@ PG_REGISTER_WITH_RESET_FN(sdcardConfig_t, sdcardConfig, PG_SDCARD_CONFIG, 0);
void pgResetFn_sdcardConfig(sdcardConfig_t *config)
{
config->useDma = false;
#ifdef SDCARD_SPI_INSTANCE
config->enabled = 1;
config->device = spiDeviceByInstance(SDCARD_SPI_INSTANCE);
#elif defined(USE_SDCARD_SDIO)
config->enabled = 1;
#else
config->enabled = 0;
config->device = 0;
#endif
#ifdef SDCARD_DETECT_PIN
config->cardDetectTag = IO_TAG(SDCARD_DETECT_PIN);
#else
config->cardDetectTag = IO_TAG_NONE;
#endif
#ifdef SDCARD_SPI_CS_PIN
config->chipSelectTag = IO_TAG(SDCARD_SPI_CS_PIN);
#else
config->chipSelectTag = IO_TAG_NONE;
config->device = SPI_DEV_TO_CFG(SPIINVALID);
config->mode = SDCARD_MODE_NONE;
// We can safely handle SPI and SDIO cases separately on custom targets, as these are exclusive per target.
// On generic targets, SPI has precedence over SDIO; SDIO must be post-flash configured.
#ifdef USE_SDCARD_SDIO
config->mode = SDCARD_MODE_SDIO;
config->enabled = 1;
#endif
#ifdef SDCARD_DETECT_INVERTED
config->cardDetectInverted = 1;
#else
config->cardDetectInverted = 0;
#ifdef USE_SDCARD_SPI
SPIDevice spidevice = spiDeviceByInstance(SDCARD_SPI_INSTANCE);
config->device = SPI_DEV_TO_CFG(spidevice);
config->chipSelectTag = IO_TAG(SDCARD_SPI_CS_PIN);
if (spidevice != SPIINVALID && config->chipSelectTag) {
config->enabled = 1;
config->mode = SDCARD_MODE_SPI;
}
#endif
config->cardDetectTag = IO_TAG(SDCARD_DETECT_PIN);
config->cardDetectInverted = SDCARD_DETECT_IS_INVERTED;
#if defined(SDCARD_DMA_STREAM_TX_FULL)
config->dmaIdentifier = (uint8_t)dmaGetIdentifier(SDCARD_DMA_STREAM_TX_FULL);
#elif defined(SDCARD_DMA_CHANNEL_TX)

View File

@ -23,15 +23,22 @@
#include "pg/pg.h"
#include "drivers/io.h"
typedef enum {
SDCARD_MODE_NONE = 0,
SDCARD_MODE_SPI,
SDCARD_MODE_SDIO
} sdcardMode_e;
typedef struct sdcardConfig_s {
uint8_t useDma;
uint8_t enabled;
uint8_t device;
int8_t device;
ioTag_t cardDetectTag;
ioTag_t chipSelectTag;
uint8_t cardDetectInverted;
uint8_t dmaIdentifier;
uint8_t dmaChannel;
sdcardMode_e mode;
} sdcardConfig_t;
PG_DECLARE(sdcardConfig_t, sdcardConfig);

View File

@ -68,6 +68,7 @@
#define USE_BARO_BMP280
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB11
#define SDCARD_SPI_INSTANCE SPI2

View File

@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
FEATURES += SDCARD VCP ONBOARDFLASH
FEATURES += SDCARD_SPI VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \

View File

@ -82,6 +82,7 @@
#define BMP280_SPI_INSTANCE SPI3
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB11
#define SDCARD_SPI_INSTANCE SPI2

View File

@ -1,5 +1,5 @@
F7X2RE_TARGETS += $(TARGET)
FEATURES += SDCARD VCP ONBOARDFLASH
FEATURES += SDCARD_SPI VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \

View File

@ -135,6 +135,7 @@
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PD3
#define SDCARD_SPI_INSTANCE SPI4

View File

@ -1,5 +1,5 @@
F7X5XG_TARGETS += $(TARGET)
FEATURES += SDCARD VCP
FEATURES += SDCARD_SPI VCP
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \

View File

@ -62,6 +62,7 @@
#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_ST0_HANDLER
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_PIN PC3
#define SDCARD_DETECT_INVERTED
#define SDCARD_SPI_INSTANCE SPI2

View File

@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
FEATURES += VCP SDCARD
FEATURES += VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_spi_icm20689.c \

View File

@ -120,6 +120,7 @@
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2

View File

@ -1,6 +1,6 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP SDCARD
FEATURES = VCP SDCARD_SPI
TARGET_FLAGS = -DSPRACINGF3
TARGET_SRC = \

View File

@ -73,6 +73,7 @@
#define MS5611_I2C_INSTANCE I2CDEV_1
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PD2
#define SDCARD_SPI_INSTANCE SPI3

View File

@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
FEATURES += SDCARD VCP ONBOARDFLASH
FEATURES += SDCARD_SPI VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6500.c \

View File

@ -46,6 +46,7 @@
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN

View File

@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP SDCARD
FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/compass/compass_hmc5883l.c \

View File

@ -70,6 +70,7 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_PIN PB7
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN

View File

@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
FEATURES = VCP SDCARD ONBOARDFLASH
FEATURES = VCP SDCARD_SPI ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_mpu6500.c \

View File

@ -65,6 +65,7 @@
//define use SD card
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_PIN PA8
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN

View File

@ -1,5 +1,5 @@
F7X2RE_TARGETS += $(TARGET)
FEATURES += VCP ONBOARDFLASH SDCARD
FEATURES += VCP ONBOARDFLASH SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_mpu6500.c \

View File

@ -61,6 +61,7 @@
#define USE_BARO_MS5611
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN PE15
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream3

View File

@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
FEATURES += SDCARD VCP
FEATURES += SDCARD_SPI VCP
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \

View File

@ -106,6 +106,7 @@
// *************** SDCARD *****************************
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB7
#define SDCARD_SPI_INSTANCE SPI3

View File

@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
FEATURES += SDCARD VCP ONBOARDFLASH
FEATURES += SDCARD_SPI VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6500.c \

View File

@ -127,6 +127,7 @@
#define SPI1_MOSI_PIN PA7
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB5
#define SDCARD_SPI_INSTANCE SPI1

View File

@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP SDCARD
FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \

View File

@ -63,6 +63,7 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB7
#define SDCARD_SPI_INSTANCE SPI2

View File

@ -1,6 +1,6 @@
F405_TARGETS += $(TARGET)
FEATURES = VCP SDCARD
FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \

View File

@ -116,6 +116,7 @@
#else
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB2
#define SDCARD_SPI_INSTANCE SPI2

View File

@ -2,7 +2,7 @@ F3_TARGETS += $(TARGET)
ifeq ($(TARGET), FURYF3OSD)
FEATURES += VCP ONBOARDFLASH
else
FEATURES += VCP SDCARD
FEATURES += VCP SDCARD_SPI
endif
TARGET_SRC = \

View File

@ -76,6 +76,7 @@
#define MS5611_I2C_INSTANCE I2CDEV_1
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PD2
#define SDCARD_SPI_INSTANCE SPI2

View File

@ -2,7 +2,7 @@ F405_TARGETS += $(TARGET)
ifeq ($(TARGET), FURYF4OSD)
FEATURES += VCP ONBOARDFLASH
else
FEATURES += VCP ONBOARDFLASH SDCARD
FEATURES += VCP ONBOARDFLASH SDCARD_SPI
endif
TARGET_SRC = \

View File

@ -78,6 +78,7 @@
#define SPI4_MOSI_PIN PE14
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PD2
#define SDCARD_SPI_INSTANCE SPI4

View File

@ -1,5 +1,5 @@
F7X5XG_TARGETS += $(TARGET)
FEATURES += SDCARD VCP ONBOARDFLASH
FEATURES += SDCARD_SPI VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_spi_icm20689.c

0
src/main/target/HAKRCF722/target.mk Executable file → Normal file
View File

0
src/main/target/KAKUTEF4/FLYWOOF405.mk Executable file → Normal file
View File

View File

@ -123,6 +123,7 @@
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PD8
#define SDCARD_SPI_INSTANCE SPI1

View File

@ -4,7 +4,7 @@ else
F7X5XG_TARGETS += $(TARGET)
endif
FEATURES += SDCARD VCP
FEATURES += SDCARD_SPI VCP
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \

View File

@ -81,6 +81,7 @@
#if defined(KIWIF4V2)
#define USE_SDCARD
#define USE_SDCARD_SPI
//#define SDCARD_DETECT_PIN PB9
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN PB12

View File

@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
FEATURES += VCP ONBOARDFLASH SDCARD
FEATURES += VCP ONBOARDFLASH SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \

View File

@ -66,6 +66,7 @@
#define USE_BARO_MS5611
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC13
#define SDCARD_SPI_INSTANCE SPI3

View File

@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
FEATURES += VCP SDCARD
FEATURES += VCP SDCARD_SPI
HSE_VALUE = 16000000
TARGET_SRC = \

View File

@ -77,6 +77,7 @@
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC13
#define SDCARD_SPI_INSTANCE SPI2

View File

@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP SDCARD
FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \

View File

@ -104,6 +104,7 @@
// *************** SD Card **************************
#define USE_SDCARD
#define USE_SDCARD_SPI
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define SDCARD_SPI_INSTANCE SPI3
#define SDCARD_SPI_CS_PIN PC1

View File

@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
FEATURES += VCP ONBOARDFLASH SDCARD
FEATURES += VCP ONBOARDFLASH SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6500.c \

View File

@ -1,5 +1,5 @@
F411_TARGETS += $(TARGET)
FEATURES += SDCARD VCP
FEATURES += SDCARD_SPI VCP
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6500.c \

View File

@ -1,6 +1,6 @@
F411_TARGETS += $(TARGET)
FEATURES += VCP SDCARD
FEATURES += VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \

View File

@ -86,6 +86,7 @@
// *************** SD Card **************************
#define USE_SDCARD
#define USE_SDCARD_SPI
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define USE_SPI_DEVICE_3

View File

@ -1,5 +1,5 @@
F7X2RE_TARGETS += $(TARGET)
FEATURES += SDCARD VCP
FEATURES += SDCARD_SPI VCP
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6500.c \

View File

@ -82,9 +82,10 @@
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN PB12
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
#define USE_SDCARD_SPI
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN PB12
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
#define USE_ADC
#define ADC_INSTANCE ADC1

View File

@ -1,6 +1,6 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP SDCARD
FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \

View File

@ -116,6 +116,7 @@
#define USE_SPI_DEVICE_2 // SDcard
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC13
#define SDCARD_SPI_INSTANCE SPI2

View File

@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
FEATURES += SDCARD VCP
FEATURES += SDCARD_SPI VCP
ifeq ($(TARGET), MLTEMPF4)
TARGET_SRC = \

View File

@ -54,6 +54,7 @@
#define GYRO_1_ALIGN CW0_DEG
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PD2
#define SDCARD_SPI_INSTANCE SPI3

View File

@ -1,5 +1,5 @@
F7X2RE_TARGETS += $(TARGET)
FEATURES += SDCARD VCP
FEATURES += SDCARD_SPI VCP
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6500.c \

View File

@ -124,6 +124,7 @@
#define SPI4_MOSI_PIN PE14
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PF14
#define SDCARD_SPI_INSTANCE SPI4

View File

@ -1,5 +1,5 @@
F7X6XG_TARGETS += $(TARGET)
FEATURES += SDCARD VCP
FEATURES += SDCARD_SPI VCP
TARGET_SRC = \
drivers/accgyro/accgyro_fake.c \

View File

@ -1,5 +1,5 @@
F7X2RE_TARGETS += $(TARGET)
FEATURES += VCP SDIO
FEATURES += VCP SDCARD_SDIO
TARGET_SRC = \
drivers/accgyro/accgyro_fake.c \

View File

@ -142,6 +142,7 @@
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2

View File

@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP SDCARD
FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \

View File

@ -1,2 +1,2 @@
#EXUAVF4PRO
FEATURES = VCP SDCARD
FEATURES = VCP SDCARD_SPI

View File

@ -1,2 +1,2 @@
# the OMNIBUSF4SD has an SDCARD instead of flash, a BMP280 baro and therefore a slightly different ppm/pwm and SPI mapping
FEATURES = VCP SDCARD
FEATURES = VCP SDCARD_SPI

View File

@ -152,6 +152,7 @@
#if defined(OMNIBUSF4SD)
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB7
#define SDCARD_SPI_INSTANCE SPI2

View File

@ -184,6 +184,7 @@
//SD-----------------------------------------
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PE3
#define SDCARD_SPI_INSTANCE SPI4

View File

@ -2,7 +2,7 @@ F7X5XG_TARGETS += $(TARGET)
ifeq ($(TARGET), FPVM_BETAFLIGHTF7)
FEATURES = VCP ONBOARDFLASH
else
FEATURES = VCP SDCARD
FEATURES = VCP SDCARD_SPI
endif
TARGET_SRC = \

View File

@ -159,6 +159,7 @@
// SDCARD support for AIRBOTF4SD
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC0
#define SDCARD_SPI_INSTANCE SPI3

View File

@ -1,6 +1,6 @@
F405_TARGETS += $(TARGET)
ifeq ($(TARGET), AIRBOTF4SD)
FEATURES = VCP SDCARD
FEATURES = VCP SDCARD_SPI
else
FEATURES = VCP ONBOARDFLASH
endif

View File

@ -69,6 +69,7 @@
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI1

View File

@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP SDCARD
FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \

View File

@ -143,6 +143,7 @@
#define RTC6705_CS_PIN PC14
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_GPIO SPI2_GPIO
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN

View File

@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP SDCARD
FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \

View File

@ -1,5 +1,5 @@
SITL_TARGETS += $(TARGET)
#FEATURES += SDCARD VCP
FEATURES += #SDCARD_SPI VCP
TARGET_SRC = \
drivers/accgyro/accgyro_fake.c \

View File

@ -157,6 +157,7 @@
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2

View File

@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP SDCARD
FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \

View File

@ -179,6 +179,7 @@
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2

View File

@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP SDCARD
FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \

View File

@ -140,6 +140,7 @@
#define SPI_SHARED_MAX7456_AND_RTC6705
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2

View File

@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP SDCARD
FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \

View File

@ -148,6 +148,7 @@
#endif
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2

View File

@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
FEATURES = VCP SDCARD
FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \

View File

@ -161,6 +161,7 @@
//#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_ST0_HANDLER
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2

View File

@ -1,5 +1,5 @@
F405_TARGETS += $(TARGET)
FEATURES = VCP SDCARD
FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \

View File

@ -149,6 +149,7 @@
#define SPI3_MOSI_PIN PB5
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_SPI_INSTANCE SPI3
#define SDCARD_SPI_CS_PIN PC3
#define SDCARD_DMA_STREAM_TX_FULL DMA1_Stream7

View File

@ -1,5 +1,5 @@
F7X2RE_TARGETS += $(TARGET)
FEATURES = VCP SDCARD
FEATURES = VCP SDCARD_SPI
TARGET_SRC = \
drivers/accgyro/accgyro_fake.c \

View File

@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP SDCARD ONBOARDFLASH
FEATURES = VCP SDCARD_SPI ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_fake.c \

View File

@ -95,6 +95,7 @@
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN PD8
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5

Some files were not shown because too many files have changed in this diff Show More