diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h
index 6b1febc8f..990eb0514 100644
--- a/Marlin/Configuration_adv.h
+++ b/Marlin/Configuration_adv.h
@@ -1326,9 +1326,6 @@
*/
//#define USB_FLASH_DRIVE_SUPPORT
#if ENABLED(USB_FLASH_DRIVE_SUPPORT)
- #define USB_CS_PIN SDSS
- #define USB_INTR_PIN SD_DETECT_PIN
-
/**
* USB Host Shield Library
*
@@ -1339,7 +1336,18 @@
* is less tested and is known to interfere with Servos.
* [1] This requires USB_INTR_PIN to be interrupt-capable.
*/
+ //#define USE_UHS2_USB
//#define USE_UHS3_USB
+
+ /**
+ * Native USB Host supported by some boards (USB OTG)
+ */
+ //#define USE_OTG_USB_HOST
+
+ #if DISABLED(USE_OTG_USB_HOST)
+ #define USB_CS_PIN SDSS
+ #define USB_INTR_PIN SD_DETECT_PIN
+ #endif
#endif
/**
diff --git a/Marlin/src/HAL/STM32/usb_host.cpp b/Marlin/src/HAL/STM32/usb_host.cpp
new file mode 100644
index 000000000..ed743361e
--- /dev/null
+++ b/Marlin/src/HAL/STM32/usb_host.cpp
@@ -0,0 +1,117 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program 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.
+ *
+ * This program 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 this program. If not, see .
+ *
+ */
+
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../inc/MarlinConfig.h"
+
+#if BOTH(USE_OTG_USB_HOST, USBHOST)
+
+#include "usb_host.h"
+#include "../shared/Marduino.h"
+#include "usbh_core.h"
+#include "usbh_msc.h"
+
+USBH_HandleTypeDef hUsbHost;
+USBHost usb;
+BulkStorage bulk(&usb);
+
+static void USBH_UserProcess(USBH_HandleTypeDef *phost, uint8_t id) {
+ switch(id) {
+ case HOST_USER_SELECT_CONFIGURATION:
+ //SERIAL_ECHOLNPGM("APPLICATION_SELECT_CONFIGURATION");
+ break;
+ case HOST_USER_DISCONNECTION:
+ //SERIAL_ECHOLNPGM("APPLICATION_DISCONNECT");
+ //usb.setUsbTaskState(USB_STATE_RUNNING);
+ break;
+ case HOST_USER_CLASS_ACTIVE:
+ //SERIAL_ECHOLNPGM("APPLICATION_READY");
+ usb.setUsbTaskState(USB_STATE_RUNNING);
+ break;
+ case HOST_USER_CONNECTION:
+ break;
+ default:
+ break;
+ }
+}
+
+bool USBHost::start() {
+ if (USBH_Init(&hUsbHost, USBH_UserProcess, TERN(USE_USB_HS_IN_FS, HOST_HS, HOST_FS)) != USBH_OK) {
+ SERIAL_ECHOLNPGM("Error: USBH_Init");
+ return false;
+ }
+ if (USBH_RegisterClass(&hUsbHost, USBH_MSC_CLASS) != USBH_OK) {
+ SERIAL_ECHOLNPGM("Error: USBH_RegisterClass");
+ return false;
+ }
+ if (USBH_Start(&hUsbHost) != USBH_OK) {
+ SERIAL_ECHOLNPGM("Error: USBH_Start");
+ return false;
+ }
+ return true;
+}
+
+void USBHost::Task() {
+ USBH_Process(&hUsbHost);
+}
+
+uint8_t USBHost::getUsbTaskState() {
+ return usb_task_state;
+}
+
+void USBHost::setUsbTaskState(uint8_t state) {
+ usb_task_state = state;
+ if (usb_task_state == USB_STATE_RUNNING) {
+ MSC_LUNTypeDef info;
+ USBH_MSC_GetLUNInfo(&hUsbHost, usb.lun, &info);
+ capacity = info.capacity.block_nbr / 2000;
+ block_size = info.capacity.block_size;
+ block_count = info.capacity.block_nbr;
+ // SERIAL_ECHOLNPAIR("info.capacity.block_nbr : %ld\n", info.capacity.block_nbr);
+ // SERIAL_ECHOLNPAIR("info.capacity.block_size: %d\n", info.capacity.block_size);
+ // SERIAL_ECHOLNPAIR("capacity : %d MB\n", capacity);
+ }
+};
+
+bool BulkStorage::LUNIsGood(uint8_t t) {
+ return USBH_MSC_IsReady(&hUsbHost) && USBH_MSC_UnitIsReady(&hUsbHost, t);
+}
+
+uint32_t BulkStorage::GetCapacity(uint8_t lun) {
+ return usb->block_count;
+}
+
+uint16_t BulkStorage::GetSectorSize(uint8_t lun) {
+ return usb->block_size;
+}
+
+uint8_t BulkStorage::Read(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t blocks, uint8_t *buf) {
+ return USBH_MSC_Read(&hUsbHost, lun, addr, buf, blocks) != USBH_OK;
+}
+
+uint8_t BulkStorage::Write(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t blocks, const uint8_t * buf) {
+ return USBH_MSC_Write(&hUsbHost, lun, addr, const_cast (buf), blocks) != USBH_OK;
+}
+
+#endif // USE_OTG_USB_HOST && USBHOST
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/usb_host.h b/Marlin/src/HAL/STM32/usb_host.h
new file mode 100644
index 000000000..c0001c0d7
--- /dev/null
+++ b/Marlin/src/HAL/STM32/usb_host.h
@@ -0,0 +1,60 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program 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.
+ *
+ * This program 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 this program. If not, see .
+ *
+ */
+#pragma once
+
+#include
+
+typedef enum {
+ USB_STATE_INIT,
+ USB_STATE_ERROR,
+ USB_STATE_RUNNING,
+} usb_state_t;
+
+class USBHost {
+public:
+ bool start();
+ void Task();
+ uint8_t getUsbTaskState();
+ void setUsbTaskState(uint8_t state);
+ uint8_t regRd(uint8_t reg) { return 0x0; };
+ uint8_t usb_task_state = USB_STATE_INIT;
+ uint8_t lun = 0;
+ uint32_t capacity = 0;
+ uint16_t block_size = 0;
+ uint32_t block_count = 0;
+};
+
+class BulkStorage {
+public:
+ BulkStorage(USBHost *usb) : usb(usb) {};
+
+ bool LUNIsGood(uint8_t t);
+ uint32_t GetCapacity(uint8_t lun);
+ uint16_t GetSectorSize(uint8_t lun);
+ uint8_t Read(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t blocks, uint8_t *buf);
+ uint8_t Write(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t blocks, const uint8_t * buf);
+
+ USBHost *usb;
+};
+
+extern USBHost usb;
+extern BulkStorage bulk;
diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h
index 93f912e5c..dda029874 100644
--- a/Marlin/src/inc/Conditionals_adv.h
+++ b/Marlin/src/inc/Conditionals_adv.h
@@ -386,6 +386,10 @@
#define HOMING_BUMP_MM { 0, 0, 0 }
#endif
+#if ENABLED(USB_FLASH_DRIVE_SUPPORT) && NONE(USE_OTG_USB_HOST, USE_UHS3_USB)
+ #define USE_UHS2_USB
+#endif
+
/**
* Driver Timings (in nanoseconds)
* NOTE: Driver timing order is longest-to-shortest duration.
diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h
index 6121c5ed1..62c954c89 100644
--- a/Marlin/src/inc/SanityCheck.h
+++ b/Marlin/src/inc/SanityCheck.h
@@ -2912,10 +2912,14 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
#error "PRINTCOUNTER requires EEPROM_SETTINGS."
#endif
-#if ENABLED(USB_FLASH_DRIVE_SUPPORT) && !PINS_EXIST(USB_CS, USB_INTR)
+#if ENABLED(USB_FLASH_DRIVE_SUPPORT) && !PINS_EXIST(USB_CS, USB_INTR) && DISABLED(USE_OTG_USB_HOST)
#error "USB_CS_PIN and USB_INTR_PIN are required for USB_FLASH_DRIVE_SUPPORT."
#endif
+#if ENABLED(USE_OTG_USB_HOST) && !defined(HAS_OTG_USB_HOST_SUPPORT)
+ #error "The current board does not support USE_OTG_USB_HOST."
+#endif
+
#if ENABLED(SD_FIRMWARE_UPDATE) && !defined(__AVR_ATmega2560__)
#error "SD_FIRMWARE_UPDATE requires an ATmega2560-based (Arduino Mega) board."
#endif
diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h
index e6a1e9299..b3cfe5b6b 100644
--- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h
+++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h
@@ -52,6 +52,13 @@
#define SPI_DEVICE 2
+//
+// Servos
+//
+#ifndef SERVO0_PIN
+ #define SERVO0_PIN PA8 // Enable BLTOUCH support on IO0 (WIFI connector)
+#endif
+
//
// Limit Switches
//
@@ -91,6 +98,7 @@
#ifndef DEFAULT_PWM_MOTOR_CURRENT
#define DEFAULT_PWM_MOTOR_CURRENT { 800, 800, 800 }
#endif
+
//
// Temperature Sensors
//
@@ -111,10 +119,6 @@
#define POWER_LOSS_PIN PA2 // PW_DET
#define PS_ON_PIN PA3 // PW_OFF
-#ifndef SERVO0_PIN
- #define SERVO0_PIN PA8 // Enable BLTOUCH support on IO0 (WIFI connector)
-#endif
-
#define MT_DET_1_PIN PA4
#define MT_DET_PIN_INVERTING false
diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h
index bfa400765..d594e3ca4 100644
--- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h
+++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h
@@ -35,6 +35,9 @@
#define I2C_EEPROM
#define MARLIN_EEPROM_SIZE 0x2000 // 8KB (24C64 ... 64Kb = 8KB)
+// USB Flash Drive support
+#define HAS_OTG_USB_HOST_SUPPORT
+
#define TP // Enable to define servo and probe pins
//
diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h
index 235ed1edc..be05ebcfa 100644
--- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h
+++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h
@@ -44,6 +44,9 @@
#define FLASH_EEPROM_LEVELING
#endif
+// USB Flash Drive support
+#define HAS_OTG_USB_HOST_SUPPORT
+
//
// Servos
//
diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h
index f0fc99e0c..81edff679 100644
--- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h
+++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h
@@ -41,6 +41,7 @@
//#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation
//#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation
#define I2C_EEPROM
+#define MARLIN_EEPROM_SIZE 0x1000 // 4KB
//
// Release PB4 (Z_DIR_PIN) from JTAG NRST role
diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h
index 333634046..719f8773f 100644
--- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h
+++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h
@@ -36,6 +36,10 @@
//#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation
//#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation
#define I2C_EEPROM
+#define MARLIN_EEPROM_SIZE 0x1000 // 4KB
+
+// USB Flash Drive support
+#define HAS_OTG_USB_HOST_SUPPORT
//
// Release PB4 (Y_ENABLE_PIN) from JTAG NRST role
diff --git a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp
index 539d31654..28a18cd9d 100644
--- a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp
+++ b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp
@@ -44,8 +44,9 @@
#include "../../core/serial.h"
#include "../../module/temperature.h"
-static_assert(USB_CS_PIN != -1, "USB_CS_PIN must be defined");
-static_assert(USB_INTR_PIN != -1, "USB_INTR_PIN must be defined");
+#if DISABLED(USE_OTG_USB_HOST) && !PINS_EXIST(USB_CS, USB_INTR)
+ #error "USB_FLASH_DRIVE_SUPPORT requires USB_CS_PIN and USB_INTR_PIN to be defined."
+#endif
#if ENABLED(USE_UHS3_USB)
#define NO_AUTO_SPEED
@@ -81,6 +82,17 @@ static_assert(USB_INTR_PIN != -1, "USB_INTR_PIN must be defined");
#define UHS_START (usb.Init() == 0)
#define UHS_STATE(state) UHS_USB_HOST_STATE_##state
+#elif ENABLED(USE_OTG_USB_HOST)
+
+ #if HAS_SD_HOST_DRIVE
+ #include HAL_PATH(../../HAL, msc_sd.h)
+ #endif
+
+ #include HAL_PATH(../../HAL, usb_host.h)
+
+ #define UHS_START usb.start()
+ #define rREVISION 0
+ #define UHS_STATE(state) USB_STATE_##state
#else
#include "lib-uhs2/Usb.h"
#include "lib-uhs2/masstorage.h"
@@ -250,7 +262,7 @@ bool Sd2Card::isInserted() {
return state == MEDIA_READY;
}
-bool Sd2Card::ready() {
+bool Sd2Card::isReady() {
return state > DO_STARTUP;
}
diff --git a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.h b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.h
index 8ca95ba70..83245168a 100644
--- a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.h
+++ b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.h
@@ -23,26 +23,27 @@
/**
* \file
- * \brief Sd2Card class for V2 SD/SDHC cards
+ * \brief Sd2Card class for USB Flash Drive
*/
-
#include "../SdFatConfig.h"
#include "../SdInfo.h"
-/**
- * Define SOFTWARE_SPI to use bit-bang SPI
- */
-#if EITHER(MEGA_SOFT_SPI, USE_SOFTWARE_SPI)
- #define SOFTWARE_SPI
-#endif
+#if DISABLED(USE_OTG_USB_HOST)
+ /**
+ * Define SOFTWARE_SPI to use bit-bang SPI
+ */
+ #if EITHER(MEGA_SOFT_SPI, USE_SOFTWARE_SPI)
+ #define SOFTWARE_SPI
+ #endif
-// SPI pin definitions - do not edit here - change in SdFatConfig.h
-#if ENABLED(SOFTWARE_SPI)
- #warning "Auto-assigning '10' as the SD_CHIP_SELECT_PIN."
- #define SD_CHIP_SELECT_PIN 10 // Software SPI chip select pin for the SD
-#else
- // hardware pin defs
- #define SD_CHIP_SELECT_PIN SS_PIN // The default chip select pin for the SD card is SS.
+ // SPI pin definitions - do not edit here - change in SdFatConfig.h
+ #if ENABLED(SOFTWARE_SPI)
+ #warning "Auto-assigning '10' as the SD_CHIP_SELECT_PIN."
+ #define SD_CHIP_SELECT_PIN 10 // Software SPI chip select pin for the SD
+ #else
+ // hardware pin defs
+ #define SD_CHIP_SELECT_PIN SS_PIN // The default chip select pin for the SD card is SS.
+ #endif
#endif
class Sd2Card {
@@ -54,22 +55,24 @@ class Sd2Card {
public:
static bool usbStartup();
- bool init(const uint8_t sckRateID=0, const pin_t chipSelectPin=SD_CHIP_SELECT_PIN);
+ bool init(const uint8_t sckRateID=0, const pin_t chipSelectPin=TERN(USE_OTG_USB_HOST, 0, SD_CHIP_SELECT_PIN));
static void idle();
- inline bool readStart(const uint32_t block) { pos = block; return ready(); }
+ inline bool readStart(const uint32_t block) { pos = block; return isReady(); }
inline bool readData(uint8_t* dst) { return readBlock(pos++, dst); }
inline bool readStop() const { return true; }
- inline bool writeStart(const uint32_t block, const uint32_t) { pos = block; return ready(); }
+ inline bool writeStart(const uint32_t block, const uint32_t) { pos = block; return isReady(); }
inline bool writeData(uint8_t* src) { return writeBlock(pos++, src); }
inline bool writeStop() const { return true; }
bool readBlock(uint32_t block, uint8_t* dst);
bool writeBlock(uint32_t blockNumber, const uint8_t* src);
+ bool readCSD(csd_t* csd) { return true; };
+
uint32_t cardSize();
static bool isInserted();
- static bool ready();
+ bool isReady();
};
diff --git a/platformio.ini b/platformio.ini
index 2aff7aad2..3e87968ee 100644
--- a/platformio.ini
+++ b/platformio.ini
@@ -59,7 +59,7 @@ default_src_filter = + - - +
- -
-
-
- -
+ - -
-
-
-
@@ -272,7 +272,8 @@ HAS_DGUS_LCD = src_filter=+ +
EXTUI_EXAMPLE = src_filter=+
MALYAN_LCD = src_filter=+
-USB_FLASH_DRIVE_SUPPORT = src_filter=+
+USE_UHS2_USB = src_filter=+
+USE_UHS3_USB = src_filter=+
AUTO_BED_LEVELING_BILINEAR = src_filter=+
AUTO_BED_LEVELING_(3POINT|(BI)?LINEAR) = src_filter=+
MESH_BED_LEVELING = src_filter=+ +
@@ -1278,6 +1279,23 @@ extra_scripts = ${common.extra_scripts}
debug_tool = stlink
debug_init_break =
+#
+# USB Flash Drive mix-ins for STM32
+#
+[stm32_flash_drive]
+platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc.zip
+build_flags = ${common_stm32.build_flags}
+ -DHAL_PCD_MODULE_ENABLED -DHAL_HCD_MODULE_ENABLED
+ -DUSBHOST -DUSBH_IRQ_PRIO=3 -DUSBH_IRQ_SUBPRIO=4
+
+#
+# BigTreeTech SKR Pro (STM32F407ZGT6 ARM Cortex-M4) with USB Flash Drive Support
+#
+[env:BIGTREE_SKR_PRO_usb_flash_drive]
+extends = env:BIGTREE_SKR_PRO
+platform_packages = ${stm32_flash_drive.platform_packages}
+build_flags = ${stm32_flash_drive.build_flags}
+
#
# Bigtreetech GTR V1.0 (STM32F407IGT6 ARM Cortex-M4)
#
@@ -1290,6 +1308,14 @@ extra_scripts = ${common.extra_scripts}
build_flags = ${common_stm32.build_flags}
-DSTM32F407IX -DVECT_TAB_OFFSET=0x8000
+#
+# Bigtreetech GTR V1.0 (STM32F407IGT6 ARM Cortex-M4) with USB Flash Drive Support
+#
+[env:BIGTREE_GTR_V1_0_usb_flash_drive]
+extends = env:BIGTREE_GTR_V1_0
+platform_packages = ${stm32_flash_drive.platform_packages}
+build_flags = ${stm32_flash_drive.build_flags}
+
#
# BigTreeTech BTT002 V1.0 (STM32F407VGT6 ARM Cortex-M4)
#
@@ -1392,13 +1418,16 @@ extra_scripts = ${common.extra_scripts}
#
[env:mks_robin_pro2]
platform = ${common_stm32.platform}
+platform_packages = ${stm32_flash_drive.platform_packages}
extends = common_stm32
-build_flags = ${common_stm32.build_flags} -DHAL_HCD_MODULE_ENABLED -DUSBHOST
+build_flags = ${stm32_flash_drive.build_flags}
board = genericSTM32F407VET6
board_build.core = stm32
board_build.variant = MARLIN_F4x7Vx
board_build.ldscript = ldscript.ld
board_build.firmware = firmware.bin
+board_build.offset = 0x0000
+board_upload.offset_address = 0x08000000
build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC
debug_tool = jlink
upload_protocol = jlink
@@ -1427,6 +1456,21 @@ extra_scripts = ${common.extra_scripts}
pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py
buildroot/share/PlatformIO/scripts/stm32_bootloader.py
+#
+# MKS Robin Nano V3 with USB Flash Drive Support
+# Currently, using a STM32duino fork, until USB Host get merged
+#
+[env:mks_robin_nano_v3_usb_flash_drive]
+extends = env:mks_robin_nano_v3
+platform_packages = ${stm32_flash_drive.platform_packages}
+build_flags = ${stm32_flash_drive.build_flags}
+ -DUSBCON
+ -DUSE_USBHOST_HS
+ -DUSBD_IRQ_PRIO=5
+ -DUSBD_IRQ_SUBPRIO=6
+ -DUSE_USB_HS_IN_FS
+ -DUSBD_USE_CDC
+
#################################
# #
# Other Architectures #