Skip to content

Commit

Permalink
Add USB MSC support for H7
Browse files Browse the repository at this point in the history
  • Loading branch information
Steve Evans committed Oct 30, 2020
1 parent ae62f46 commit 31b06cd
Show file tree
Hide file tree
Showing 22 changed files with 205 additions and 53 deletions.
32 changes: 16 additions & 16 deletions make/mcu/STM32H7.mk
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ USBHID_SRC = $(notdir $(wildcard $(USBHID_DIR)/Src/*.c))

USBMSC_DIR = $(ROOT)/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC
USBMSC_SRC = $(notdir $(wildcard $(USBMSC_DIR)/Src/*.c))
EXCLUDES = usbd_msc_storage_template.c usbd_msc_scsi.c
EXCLUDES = usbd_msc_storage_template.c
USBMSC_SRC := $(filter-out ${EXCLUDES}, $(USBMSC_SRC))

VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src:$(USBHID_DIR)/Src:$(USBMSC_DIR)/Src
Expand Down Expand Up @@ -259,10 +259,10 @@ MCU_EXCLUDES = \
drivers/bus_i2c.c \
drivers/timer.c

#MSC_SRC = \
# drivers/usb_msc_common.c \
# drivers/usb_msc_h7xx.c \
# msc/usbd_storage.c
MSC_SRC = \
drivers/usb_msc_common.c \
drivers/usb_msc_h7xx.c \
msc/usbd_storage.c

ifneq ($(filter SDCARD_SDIO,$(FEATURES)),)
MCU_COMMON_SRC += \
Expand All @@ -271,17 +271,17 @@ MSC_SRC += \
msc/usbd_storage_sdio.c
endif

#ifneq ($(filter SDCARD_SPI,$(FEATURES)),)
#MSC_SRC += \
# msc/usbd_storage_sd_spi.c
#endif

#ifneq ($(filter ONBOARDFLASH,$(FEATURES)),)
#MSC_SRC += \
# msc/usbd_storage_emfat.c \
# msc/emfat.c \
# msc/emfat_file.c
#endif
ifneq ($(filter SDCARD_SPI,$(FEATURES)),)
MSC_SRC += \
msc/usbd_storage_sd_spi.c
endif

ifneq ($(filter ONBOARDFLASH,$(FEATURES)),)
MSC_SRC += \
msc/usbd_storage_emfat.c \
msc/emfat.c \
msc/emfat_file.c
endif

DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP
DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM7
Expand Down
2 changes: 1 addition & 1 deletion src/link/stm32_h750_common.ld
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ SECTIONS
. = ALIGN(4);
_ebss = .; /* define a global symbol at bss end */
__bss_end__ = _ebss;
} >RAM
} >D2_RAM

/* Uninitialized data section */
. = ALIGN(4);
Expand Down
4 changes: 2 additions & 2 deletions src/main/drivers/dshot_bitbang.c
Original file line number Diff line number Diff line change
Expand Up @@ -77,8 +77,8 @@ dshotBitbangStatus_e bbStatus;
#define BB_OUTPUT_BUFFER_ATTRIBUTE FAST_DATA_ZERO_INIT
#define BB_INPUT_BUFFER_ATTRIBUTE FAST_DATA_ZERO_INIT
#elif defined(STM32H7)
#define BB_OUTPUT_BUFFER_ATTRIBUTE DMA_RAM
#define BB_INPUT_BUFFER_ATTRIBUTE DMA_RAM
#define BB_OUTPUT_BUFFER_ATTRIBUTE __attribute__((aligned(32)))
#define BB_INPUT_BUFFER_ATTRIBUTE __attribute__((aligned(32)))
#elif defined(STM32G4)
#define BB_OUTPUT_BUFFER_ATTRIBUTE DMA_RAM_W
#define BB_INPUT_BUFFER_ATTRIBUTE DMA_RAM_R
Expand Down
1 change: 1 addition & 0 deletions src/main/drivers/flash.c
Original file line number Diff line number Diff line change
Expand Up @@ -402,6 +402,7 @@ const char *flashPartitionGetTypeName(flashPartitionType_e type)
bool flashInit(const flashConfig_t *flashConfig)
{
memset(&flashPartitionTable, 0x00, sizeof(flashPartitionTable));
flashPartitions = 0;

bool haveFlash = flashDeviceInit(flashConfig);

Expand Down
1 change: 1 addition & 0 deletions src/main/drivers/nvic.h
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,7 @@
#define NVIC_PRIO_MAG_DATA_READY NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_CALLBACK NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_MAX7456_DMA NVIC_BUILD_PRIORITY(3, 0)
#define NVIC_PRIO_SDIO_DMA NVIC_BUILD_PRIORITY(0, 0)

#ifdef USE_HAL_DRIVER
// utility macros to join/split priority
Expand Down
11 changes: 11 additions & 0 deletions src/main/drivers/persistent.c
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,17 @@ void persistentObjectWrite(persistentObjectId_e id, uint32_t value)
RTC_HandleTypeDef rtcHandle = { .Instance = RTC };

HAL_RTCEx_BKUPWrite(&rtcHandle, id, value);

#ifdef USE_SPRACING_PERSISTENT_RTC_WORKAROUND
// Also write the persistent location used by the bootloader to support DFU etc.
if (id == PERSISTENT_OBJECT_RESET_REASON) {
// SPRACING firmware sometimes enters DFU mode when MSC mode is requested
if (value == RESET_MSC_REQUEST) {
value = RESET_NONE;
}
HAL_RTCEx_BKUPWrite(&rtcHandle, PERSISTENT_OBJECT_RESET_REASON_FWONLY, value);
}
#endif
}

void persistentObjectRTCEnable(void)
Expand Down
9 changes: 9 additions & 0 deletions src/main/drivers/persistent.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,10 +29,19 @@ typedef enum {
PERSISTENT_OBJECT_MAGIC = 0,
PERSISTENT_OBJECT_HSE_VALUE,
PERSISTENT_OBJECT_OVERCLOCK_LEVEL,
#ifdef USE_SPRACING_PERSISTENT_RTC_WORKAROUND
// SPRACING H7 firmware always leaves this value reset so only use this location to invoke DFU
PERSISTENT_OBJECT_RESET_REASON_FWONLY,
#else
PERSISTENT_OBJECT_RESET_REASON,
#endif
PERSISTENT_OBJECT_RTC_HIGH, // high 32 bits of rtcTime_t
PERSISTENT_OBJECT_RTC_LOW, // low 32 bits of rtcTime_t
PERSISTENT_OBJECT_COUNT,
#ifdef USE_SPRACING_PERSISTENT_RTC_WORKAROUND
// On SPRACING H7 firmware use this alternate location for all reset reasons interpreted by this firmware
PERSISTENT_OBJECT_RESET_REASON,
#endif
} persistentObjectId_e;

// Values for PERSISTENT_OBJECT_RESET_REASON
Expand Down
21 changes: 12 additions & 9 deletions src/main/drivers/sdio_h7xx.c
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@

#include "drivers/io.h"
#include "drivers/io_impl.h"
#include "drivers/nvic.h"
#include "drivers/sdio.h"

typedef struct SD_Handle_s
Expand All @@ -50,7 +51,6 @@ typedef struct SD_Handle_s

SD_HandleTypeDef hsd1;


SD_CardInfo_t SD_CardInfo;
SD_CardType_t SD_CardType;

Expand Down Expand Up @@ -192,7 +192,7 @@ void HAL_SD_MspInit(SD_HandleTypeDef* hsd)
IOConfigGPIOAF(d3, IOCFG_SDMMC, sdioPin[SDIO_PIN_D3].af);
}

HAL_NVIC_SetPriority(sdioHardware->irqn, 0, 0);
HAL_NVIC_SetPriority(sdioHardware->irqn, NVIC_PRIORITY_BASE(NVIC_PRIO_SDIO_DMA), NVIC_PRIORITY_SUB(NVIC_PRIO_SDIO_DMA));
HAL_NVIC_EnableIRQ(sdioHardware->irqn);
}

Expand Down Expand Up @@ -537,12 +537,12 @@ SD_Error_t SD_WriteBlocks_DMA(uint64_t WriteAddress, uint32_t *buffer, uint32_t
return SD_ERROR; // unsupported.
}

/*
the SCB_CleanDCache_by_Addr() requires a 32-Byte aligned address
adjust the address and the D-Cache size to clean accordingly.
*/
uint32_t alignedAddr = (uint32_t)buffer & ~0x1F;
SCB_CleanDCache_by_Addr((uint32_t*)alignedAddr, NumberOfBlocks * BlockSize + ((uint32_t)buffer - alignedAddr));
if ((uint32_t)buffer & 0x1f) {
return SD_ADDR_MISALIGNED;
}

// Ensure the data is flushed to main memory
SCB_CleanDCache_by_Addr(buffer, NumberOfBlocks * BlockSize);

HAL_StatusTypeDef status;
if ((status = HAL_SD_WriteBlocks_DMA(&hsd1, (uint8_t *)buffer, WriteAddress, NumberOfBlocks)) != HAL_OK) {
Expand All @@ -568,13 +568,16 @@ SD_Error_t SD_ReadBlocks_DMA(uint64_t ReadAddress, uint32_t *buffer, uint32_t Bl
return SD_ERROR; // unsupported.
}

if ((uint32_t)buffer & 0x1f) {
return SD_ADDR_MISALIGNED;
}

SD_Handle.RXCplt = 1;

sdReadParameters.buffer = buffer;
sdReadParameters.BlockSize = BlockSize;
sdReadParameters.NumberOfBlocks = NumberOfBlocks;


HAL_StatusTypeDef status;
if ((status = HAL_SD_ReadBlocks_DMA(&hsd1, (uint8_t *)buffer, ReadAddress, NumberOfBlocks)) != HAL_OK) {
return SD_ERROR;
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/system_stm32h7xx.c
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ void systemReset(void)

void forcedSystemResetWithoutDisablingCaches(void)
{
persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_FORCED);
// Don't overwrite the PERSISTENT_OBJECT_RESET_REASON; just make another attempt

__disable_irq();
NVIC_SystemReset();
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/usb_msc.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#pragma once

void mscInit(void);
bool mscCheckBoot(void);
bool mscCheckBootAndReset(void);
uint8_t mscStart(void);
bool mscCheckButton(void);
void mscWaitForButton(void);
Expand Down
23 changes: 17 additions & 6 deletions src/main/drivers/usb_msc_common.c
Original file line number Diff line number Diff line change
Expand Up @@ -66,13 +66,24 @@ void mscInit(void)
}
}

bool mscCheckBoot(void)
bool mscCheckBootAndReset(void)
{
const uint32_t bootModeRequest = persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON);
return bootModeRequest == RESET_MSC_REQUEST;
// Note that we can't clear the persisent object after checking here. This is because
// this function is called multiple times during initialization. So we clear on a reset
// out of MSC mode.
static bool firstCheck = true;
static bool mscMode;

if (firstCheck) {
// Cache the bootup value of RESET_MSC_REQUEST
const uint32_t bootModeRequest = persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON);
if (bootModeRequest == RESET_MSC_REQUEST) {
mscMode = true;
// Ensure the next reset is to the configurator as the H7 processor retains the RTC value so
// a brief interruption of power is not enough to switch out of MSC mode
persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_NONE);
firstCheck = false;
}
}

return mscMode;
}

void mscSetActive(void)
Expand Down
110 changes: 110 additions & 0 deletions src/main/drivers/usb_msc_h7xx.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,110 @@
/*
* 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/>.
*/

/*
* Author: Chris Hockuba (https://github.com/conkerkh)
*
*/

#include <stdint.h>
#include <stdbool.h>
#include <string.h>

#include "platform.h"

#if defined(USE_USB_MSC)

#include "build/build_config.h"

#include "common/utils.h"

#include "blackbox/blackbox.h"
#include "drivers/io.h"
#include "drivers/nvic.h"
#include "drivers/serial_usb_vcp.h"
#include "drivers/system.h"
#include "drivers/time.h"
#include "drivers/usb_msc.h"

#include "msc/usbd_storage.h"

#include "pg/sdcard.h"
#include "pg/usb.h"

#include "vcp_hal/usbd_cdc_interface.h"

#include "usb_io.h"
#include "usbd_msc.h"

uint8_t mscStart(void)
{
//Start USB
usbGenerateDisconnectPulse();

IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, 0);
IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, 0);

USBD_Init(&USBD_Device, &VCP_Desc, 0);

/** Regsiter class */
USBD_RegisterClass(&USBD_Device, USBD_MSC_CLASS);

/** Register interface callbacks */
switch (blackboxConfig()->device) {
#ifdef USE_SDCARD
case BLACKBOX_DEVICE_SDCARD:
switch (sdcardConfig()->mode) {
#ifdef USE_SDCARD_SDIO
case SDCARD_MODE_SDIO:
USBD_MSC_RegisterStorage(&USBD_Device, &USBD_MSC_MICRO_SDIO_fops);
break;
#endif
#ifdef USE_SDCARD_SPI
case SDCARD_MODE_SPI:
USBD_MSC_RegisterStorage(&USBD_Device, &USBD_MSC_MICRO_SD_SPI_fops);
break;
#endif
default:
return 1;
}
break;
#endif

#ifdef USE_FLASHFS
case BLACKBOX_DEVICE_FLASH:
USBD_MSC_RegisterStorage(&USBD_Device, &USBD_MSC_EMFAT_fops);
break;
#endif

default:
return 1;
}

USBD_Start(&USBD_Device);

// NVIC configuration for SYSTick
NVIC_DisableIRQ(SysTick_IRQn);
NVIC_SetPriority(SysTick_IRQn, NVIC_BUILD_PRIORITY(0, 0));
NVIC_EnableIRQ(SysTick_IRQn);

return 0;
}

#endif
21 changes: 11 additions & 10 deletions src/main/fc/init.c
Original file line number Diff line number Diff line change
Expand Up @@ -337,7 +337,6 @@ void init(void)
};
uint8_t initFlags = 0;


#ifdef CONFIG_IN_SDCARD

//
Expand Down Expand Up @@ -445,6 +444,16 @@ void init(void)

systemState |= SYSTEM_STATE_CONFIG_LOADED;

#ifdef USE_SDCARD
// Ensure the SD card is initialised before the USB MSC starts to avoid a race condition
#if !defined(CONFIG_IN_SDCARD) && defined(STM32H7) && defined(USE_SDCARD_SDIO) // H7 only for now, likely should be applied to F4/F7 too
sdioPinConfigure();
SDIO_GPIO_Init();
initFlags |= SD_INIT_ATTEMPTED;
sdCardAndFSInit();
#endif
#endif

#ifdef USE_BRUSHED_ESC_AUTODETECT
// Now detect again with the actually configured pin for motor 1, if it is not the default pin.
ioTag_t configuredMotorIoTag = motorConfig()->dev.ioTags[0];
Expand Down Expand Up @@ -635,7 +644,7 @@ void init(void)
/* MSC mode will start after init, but will not allow scheduler to run,
* so there is no bottleneck in reading and writing data */
mscInit();
if (mscCheckBoot() || mscCheckButton()) {
if (mscCheckBootAndReset() || mscCheckButton()) {
ledInit(statusLedConfig());

#if defined(USE_FLASHFS)
Expand Down Expand Up @@ -686,14 +695,6 @@ void init(void)
updateHardwareRevision();
#endif

#if defined(STM32H7) && defined(USE_SDCARD_SDIO) // H7 only for now, likely should be applied to F4/F7 too
if (!(initFlags & SD_INIT_ATTEMPTED)) {
sdioPinConfigure();
SDIO_GPIO_Init();
}
#endif


#ifdef USE_VTX_RTC6705
bool useRTC6705 = rtc6705IOInit(vtxIOConfig());
#endif
Expand Down
Loading

0 comments on commit 31b06cd

Please sign in to comment.