From 8f55c74533b7106daddbfccb38b85056c8a549f5 Mon Sep 17 00:00:00 2001
From: Damien George <damien.p.george@gmail.com>
Date: Fri, 31 May 2019 22:17:02 +1000
Subject: [PATCH] stm32/boards: Add board definition files for PYBD -SF2, -SF3,
 -SF6.

These are core configurations providing PYBv1.x-level features.
---
 ports/stm32/boards/PYBD_SF2/bdev.c            |  62 ++++++
 ports/stm32/boards/PYBD_SF2/board_init.c      |  38 ++++
 ports/stm32/boards/PYBD_SF2/f722_qspi.ld      |  97 +++++++++
 ports/stm32/boards/PYBD_SF2/mpconfigboard.h   | 201 ++++++++++++++++++
 ports/stm32/boards/PYBD_SF2/mpconfigboard.mk  |  10 +
 ports/stm32/boards/PYBD_SF2/pins.csv          | 189 ++++++++++++++++
 .../boards/PYBD_SF2/stm32f7xx_hal_conf.h      |  88 ++++++++
 ports/stm32/boards/PYBD_SF3/bdev.c            |   1 +
 ports/stm32/boards/PYBD_SF3/board_init.c      |   1 +
 ports/stm32/boards/PYBD_SF3/mpconfigboard.h   |  34 +++
 ports/stm32/boards/PYBD_SF3/mpconfigboard.mk  |  13 ++
 ports/stm32/boards/PYBD_SF3/pins.csv          | 189 ++++++++++++++++
 .../boards/PYBD_SF3/stm32f7xx_hal_conf.h      |   1 +
 ports/stm32/boards/PYBD_SF6/bdev.c            |   1 +
 ports/stm32/boards/PYBD_SF6/board_init.c      |   1 +
 ports/stm32/boards/PYBD_SF6/f767.ld           |  96 +++++++++
 ports/stm32/boards/PYBD_SF6/mpconfigboard.h   |  66 ++++++
 ports/stm32/boards/PYBD_SF6/mpconfigboard.mk  |  10 +
 ports/stm32/boards/PYBD_SF6/pins.csv          | 189 ++++++++++++++++
 .../boards/PYBD_SF6/stm32f7xx_hal_conf.h      |   1 +
 20 files changed, 1288 insertions(+)
 create mode 100644 ports/stm32/boards/PYBD_SF2/bdev.c
 create mode 100644 ports/stm32/boards/PYBD_SF2/board_init.c
 create mode 100644 ports/stm32/boards/PYBD_SF2/f722_qspi.ld
 create mode 100644 ports/stm32/boards/PYBD_SF2/mpconfigboard.h
 create mode 100644 ports/stm32/boards/PYBD_SF2/mpconfigboard.mk
 create mode 100644 ports/stm32/boards/PYBD_SF2/pins.csv
 create mode 100644 ports/stm32/boards/PYBD_SF2/stm32f7xx_hal_conf.h
 create mode 100644 ports/stm32/boards/PYBD_SF3/bdev.c
 create mode 100644 ports/stm32/boards/PYBD_SF3/board_init.c
 create mode 100644 ports/stm32/boards/PYBD_SF3/mpconfigboard.h
 create mode 100644 ports/stm32/boards/PYBD_SF3/mpconfigboard.mk
 create mode 100644 ports/stm32/boards/PYBD_SF3/pins.csv
 create mode 100644 ports/stm32/boards/PYBD_SF3/stm32f7xx_hal_conf.h
 create mode 100644 ports/stm32/boards/PYBD_SF6/bdev.c
 create mode 100644 ports/stm32/boards/PYBD_SF6/board_init.c
 create mode 100644 ports/stm32/boards/PYBD_SF6/f767.ld
 create mode 100644 ports/stm32/boards/PYBD_SF6/mpconfigboard.h
 create mode 100644 ports/stm32/boards/PYBD_SF6/mpconfigboard.mk
 create mode 100644 ports/stm32/boards/PYBD_SF6/pins.csv
 create mode 100644 ports/stm32/boards/PYBD_SF6/stm32f7xx_hal_conf.h

diff --git a/ports/stm32/boards/PYBD_SF2/bdev.c b/ports/stm32/boards/PYBD_SF2/bdev.c
new file mode 100644
index 000000000..6c5ff721e
--- /dev/null
+++ b/ports/stm32/boards/PYBD_SF2/bdev.c
@@ -0,0 +1,62 @@
+/*
+ * This file is part of the MicroPython project, http://micropython.org/
+ *
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2018-2019 Damien P. George
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#include "storage.h"
+#include "qspi.h"
+
+// Shared cache for first and second SPI block devices
+STATIC mp_spiflash_cache_t spi_bdev_cache;
+
+// First external SPI flash uses software QSPI interface
+
+STATIC const mp_soft_qspi_obj_t soft_qspi_bus = {
+    .cs = MICROPY_HW_SPIFLASH_CS,
+    .clk = MICROPY_HW_SPIFLASH_SCK,
+    .io0 = MICROPY_HW_SPIFLASH_IO0,
+    .io1 = MICROPY_HW_SPIFLASH_IO1,
+    .io2 = MICROPY_HW_SPIFLASH_IO2,
+    .io3 = MICROPY_HW_SPIFLASH_IO3,
+};
+
+const mp_spiflash_config_t spiflash_config = {
+    .bus_kind = MP_SPIFLASH_BUS_QSPI,
+    .bus.u_qspi.data = (void*)&soft_qspi_bus,
+    .bus.u_qspi.proto = &mp_soft_qspi_proto,
+    .cache = &spi_bdev_cache,
+};
+
+spi_bdev_t spi_bdev;
+
+// Second external SPI flash uses hardware QSPI interface
+
+const mp_spiflash_config_t spiflash2_config = {
+    .bus_kind = MP_SPIFLASH_BUS_QSPI,
+    .bus.u_qspi.data = NULL,
+    .bus.u_qspi.proto = &qspi_proto,
+    .cache = &spi_bdev_cache,
+};
+
+spi_bdev_t spi_bdev2;
diff --git a/ports/stm32/boards/PYBD_SF2/board_init.c b/ports/stm32/boards/PYBD_SF2/board_init.c
new file mode 100644
index 000000000..3dc2c85e2
--- /dev/null
+++ b/ports/stm32/boards/PYBD_SF2/board_init.c
@@ -0,0 +1,38 @@
+/*
+ * This file is part of the MicroPython project, http://micropython.org/
+ *
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2018-2019 Damien P. George
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#include "py/mphal.h"
+#include "storage.h"
+
+void mboot_board_early_init(void) {
+    // Enable 500mA on WBUS-DIP28
+    mp_hal_pin_config(pyb_pin_W23, MP_HAL_PIN_MODE_INPUT, MP_HAL_PIN_PULL_UP, 0);
+}
+
+void board_early_init(void) {
+    // Explicitly init SPI2 because it's not enabled as a block device
+    spi_bdev_ioctl(&spi_bdev2, BDEV_IOCTL_INIT, (uint32_t)&spiflash2_config);
+}
diff --git a/ports/stm32/boards/PYBD_SF2/f722_qspi.ld b/ports/stm32/boards/PYBD_SF2/f722_qspi.ld
new file mode 100644
index 000000000..8cafb0abe
--- /dev/null
+++ b/ports/stm32/boards/PYBD_SF2/f722_qspi.ld
@@ -0,0 +1,97 @@
+/*
+    Linker script for PYBD with STM32F722/STM32F723/STM32F732/STM32F733
+
+    Memory layout for mboot configuration (this here describes the app part):
+
+    FLASH_APP   .isr_vector
+    FLASH_APP   .text
+    FLASH_APP   .data
+
+    RAM         .data
+    RAM         .bss
+    RAM         .heap
+    RAM         .stack
+*/
+
+/* Specify the memory areas */
+MEMORY
+{
+    FLASH (rx)      : ORIGIN = 0x08000000, LENGTH = 512K
+    FLASH_ISR (rx)  : ORIGIN = 0x08000000, LENGTH = 32K     /* sectors 0,1 */
+    FLASH_APP (rx)  : ORIGIN = 0x08008000, LENGTH = 480K    /* sectors 2-7 */
+    FLASH_EXT (rx)  : ORIGIN = 0x90000000, LENGTH = 2048K   /* external QSPI */
+    RAM (rwx)       : ORIGIN = 0x20000000, LENGTH = 256K    /* DTCM+SRAM1+SRAM2 */
+}
+
+/* produce a link error if there is not this amount of RAM for these sections */
+_minimum_stack_size = 2K;
+_minimum_heap_size = 16K;
+
+/* Define tho top end of the stack.  The stack is full descending so begins just
+   above last byte of RAM.  Note that EABI requires the stack to be 8-byte
+   aligned for a call. */
+_estack = ORIGIN(RAM) + LENGTH(RAM);
+
+/* RAM extents for the garbage collector */
+_ram_start = ORIGIN(RAM);
+_ram_end = ORIGIN(RAM) + LENGTH(RAM);
+_heap_start = _ebss; /* heap starts just after statically allocated memory */
+_heap_end = _ram_end - 16K; /* 16k stack */
+
+ENTRY(Reset_Handler)
+
+/* Define output sections */
+SECTIONS
+{
+    .isr_vector :
+    {
+        . = ALIGN(4);
+        KEEP(*(.isr_vector))
+        . = ALIGN(4);
+    } >FLASH_APP
+
+    .text :
+    {
+        . = ALIGN(4);
+        *(.text*)
+        *(.rodata*)
+        . = ALIGN(4);
+        _etext = .;
+    } >FLASH_APP
+
+    _sidata = LOADADDR(.data);
+
+    .data :
+    {
+        . = ALIGN(4);
+        _sdata = .;
+        *(.data*)
+
+        . = ALIGN(4);
+        _edata = .;
+    } >RAM AT> FLASH_APP
+
+    .bss :
+    {
+        . = ALIGN(4);
+        _sbss = .;
+        *(.bss*)
+        *(COMMON)
+        . = ALIGN(4);
+        _ebss = .;
+    } >RAM
+
+    .heap :
+    {
+        . = ALIGN(4);
+        . = . + _minimum_heap_size;
+        . = ALIGN(4);
+    } >RAM
+
+    .stack :
+    {
+        . = ALIGN(4);
+        . = . + _minimum_stack_size;
+        . = ALIGN(4);
+    } >RAM
+}
diff --git a/ports/stm32/boards/PYBD_SF2/mpconfigboard.h b/ports/stm32/boards/PYBD_SF2/mpconfigboard.h
new file mode 100644
index 000000000..56650ba15
--- /dev/null
+++ b/ports/stm32/boards/PYBD_SF2/mpconfigboard.h
@@ -0,0 +1,201 @@
+/*
+ * This file is part of the MicroPython project, http://micropython.org/
+ *
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2018-2019 Damien P. George
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#define MICROPY_HW_BOARD_NAME       "PYBD-SF2W"
+#define MICROPY_HW_MCU_NAME         "STM32F722IEK"
+
+#define MICROPY_PY_PYB_LEGACY       (1)
+#define MICROPY_HW_ENABLE_INTERNAL_FLASH_STORAGE (0)
+#define MICROPY_HW_HAS_SWITCH       (1)
+#define MICROPY_HW_HAS_FLASH        (1)
+#define MICROPY_HW_ENABLE_RNG       (1)
+#define MICROPY_HW_ENABLE_RTC       (1)
+#define MICROPY_HW_ENABLE_TIMER     (1)
+#define MICROPY_HW_ENABLE_SERVO     (1)
+#define MICROPY_HW_ENABLE_DAC       (1)
+#define MICROPY_HW_ENABLE_USB       (1)
+#define MICROPY_HW_ENABLE_SDCARD    (1)
+#define MICROPY_HW_ENABLE_MMCARD    (1)
+
+#define MICROPY_BOARD_EARLY_INIT    board_early_init
+void board_early_init(void);
+
+// HSE is 25MHz, run SYS at 120MHz
+#define MICROPY_HW_CLK_PLLM         (20)
+#define MICROPY_HW_CLK_PLLN         (192)
+#define MICROPY_HW_CLK_PLLP         (RCC_PLLP_DIV2)
+#define MICROPY_HW_CLK_PLLQ         (5)
+#define MICROPY_HW_FLASH_LATENCY    (FLASH_LATENCY_3)
+
+// There is an external 32kHz oscillator
+#define RTC_ASYNCH_PREDIV           (0)
+#define RTC_SYNCH_PREDIV            (0x7fff)
+#define MICROPY_HW_RTC_USE_BYPASS   (1)
+#define MICROPY_HW_RTC_USE_US       (1)
+#define MICROPY_HW_RTC_USE_CALOUT   (1)
+
+// SPI flash #1, for R/W storage
+#define MICROPY_HW_SOFTQSPI_SCK_LOW(self) (GPIOE->BSRR = (0x10000 << 11))
+#define MICROPY_HW_SOFTQSPI_SCK_HIGH(self) (GPIOE->BSRR = (1 << 11))
+#define MICROPY_HW_SOFTQSPI_NIBBLE_READ(self) ((GPIOE->IDR >> 7) & 0xf)
+#define MICROPY_HW_SPIFLASH_SIZE_BITS (16 * 1024 * 1024)
+#define MICROPY_HW_SPIFLASH_CS      (pyb_pin_QSPI1_CS)
+#define MICROPY_HW_SPIFLASH_SCK     (pyb_pin_QSPI1_CLK)
+#define MICROPY_HW_SPIFLASH_IO0     (pyb_pin_QSPI1_D0)
+#define MICROPY_HW_SPIFLASH_IO1     (pyb_pin_QSPI1_D1)
+#define MICROPY_HW_SPIFLASH_IO2     (pyb_pin_QSPI1_D2)
+#define MICROPY_HW_SPIFLASH_IO3     (pyb_pin_QSPI1_D3)
+
+// SPI flash #1, block device config
+extern const struct _mp_spiflash_config_t spiflash_config;
+extern struct _spi_bdev_t spi_bdev;
+#define MICROPY_HW_BDEV_IOCTL(op, arg) ( \
+    (op) == BDEV_IOCTL_NUM_BLOCKS ? (MICROPY_HW_SPIFLASH_SIZE_BITS / 8 / FLASH_BLOCK_SIZE) : \
+    (op) == BDEV_IOCTL_INIT ? spi_bdev_ioctl(&spi_bdev, (op), (uint32_t)&spiflash_config) : \
+    spi_bdev_ioctl(&spi_bdev, (op), (arg)) \
+)
+#define MICROPY_HW_BDEV_READBLOCKS(dest, bl, n) spi_bdev_readblocks(&spi_bdev, (dest), (bl), (n))
+#define MICROPY_HW_BDEV_WRITEBLOCKS(src, bl, n) spi_bdev_writeblocks(&spi_bdev, (src), (bl), (n))
+
+// SPI flash #2, to be memory mapped
+#define MICROPY_HW_QSPIFLASH_SIZE_BITS_LOG2 (24)
+#define MICROPY_HW_QSPIFLASH_CS     (pyb_pin_QSPI2_CS)
+#define MICROPY_HW_QSPIFLASH_SCK    (pyb_pin_QSPI2_CLK)
+#define MICROPY_HW_QSPIFLASH_IO0    (pyb_pin_QSPI2_D0)
+#define MICROPY_HW_QSPIFLASH_IO1    (pyb_pin_QSPI2_D1)
+#define MICROPY_HW_QSPIFLASH_IO2    (pyb_pin_QSPI2_D2)
+#define MICROPY_HW_QSPIFLASH_IO3    (pyb_pin_QSPI2_D3)
+
+// SPI flash #2, block device config
+extern const struct _mp_spiflash_config_t spiflash2_config;
+extern struct _spi_bdev_t spi_bdev2;
+
+// UART config
+#define MICROPY_HW_UART1_NAME       "YA"
+#define MICROPY_HW_UART1_TX         (pyb_pin_Y1)
+#define MICROPY_HW_UART1_RX         (pyb_pin_Y2)
+#define MICROPY_HW_UART2_TX         (pyb_pin_X3)
+#define MICROPY_HW_UART2_RX         (pyb_pin_X4)
+#define MICROPY_HW_UART2_RTS        (pyb_pin_X2)
+#define MICROPY_HW_UART2_CTS        (pyb_pin_X1)
+#define MICROPY_HW_UART3_NAME       "YB"
+#define MICROPY_HW_UART3_TX         (pyb_pin_Y9)
+#define MICROPY_HW_UART3_RX         (pyb_pin_Y10)
+#define MICROPY_HW_UART4_NAME       "XA"
+#define MICROPY_HW_UART4_TX         (pyb_pin_X1)
+#define MICROPY_HW_UART4_RX         (pyb_pin_X2)
+#define MICROPY_HW_UART6_TX         (pyb_pin_BT_TXD)
+#define MICROPY_HW_UART6_RX         (pyb_pin_BT_RXD)
+#define MICROPY_HW_UART6_RTS        (pyb_pin_BT_RTS)
+#define MICROPY_HW_UART6_CTS        (pyb_pin_BT_CTS)
+
+// I2C busses
+#define MICROPY_HW_I2C1_NAME        "X"
+#define MICROPY_HW_I2C1_SCL         (pyb_pin_X9)
+#define MICROPY_HW_I2C1_SDA         (pyb_pin_X10)
+#define MICROPY_HW_I2C2_NAME        "Y"
+#define MICROPY_HW_I2C2_SCL         (pyb_pin_Y9)
+#define MICROPY_HW_I2C2_SDA         (pyb_pin_Y10)
+
+// SPI busses
+#define MICROPY_HW_SPI1_NAME        "X"
+#define MICROPY_HW_SPI1_NSS         (pyb_pin_X5)
+#define MICROPY_HW_SPI1_SCK         (pyb_pin_X6)
+#define MICROPY_HW_SPI1_MISO        (pyb_pin_X7)
+#define MICROPY_HW_SPI1_MOSI        (pyb_pin_X8)
+#define MICROPY_HW_SPI2_NAME        "Y"
+#define MICROPY_HW_SPI2_NSS         (pyb_pin_Y5)
+#define MICROPY_HW_SPI2_SCK         (pyb_pin_Y6)
+#define MICROPY_HW_SPI2_MISO        (pyb_pin_Y7)
+#define MICROPY_HW_SPI2_MOSI        (pyb_pin_Y8)
+#define MICROPY_HW_SPI3_NSS         (pyb_pin_W16)
+#define MICROPY_HW_SPI3_SCK         (pyb_pin_W29)
+#define MICROPY_HW_SPI3_MISO        (pyb_pin_W50)
+#define MICROPY_HW_SPI3_MOSI        (pyb_pin_W46)
+
+// CAN busses
+#define MICROPY_HW_CAN1_NAME        "X"
+#define MICROPY_HW_CAN1_TX          (pyb_pin_X10)
+#define MICROPY_HW_CAN1_RX          (pyb_pin_X9)
+
+// USRSW is not pulled, and pressing the button makes the input go low.
+#define MICROPY_HW_USRSW_PIN        (pyb_pin_USR)
+#define MICROPY_HW_USRSW_PULL       (GPIO_PULLUP)
+#define MICROPY_HW_USRSW_EXTI_MODE  (GPIO_MODE_IT_FALLING)
+#define MICROPY_HW_USRSW_PRESSED    (0)
+
+// LEDs
+#define MICROPY_HW_LED1             (pyb_pin_LED_RED)
+#define MICROPY_HW_LED2             (pyb_pin_LED_GREEN)
+#define MICROPY_HW_LED3             (pyb_pin_LED_BLUE)
+#define MICROPY_HW_LED_ON(pin)      (mp_hal_pin_low(pin))
+#define MICROPY_HW_LED_OFF(pin)     (mp_hal_pin_high(pin))
+
+// SD card
+#define MICROPY_HW_SDMMC2_CK                (pyb_pin_SD_CK)
+#define MICROPY_HW_SDMMC2_CMD               (pyb_pin_SD_CMD)
+#define MICROPY_HW_SDMMC2_D0                (pyb_pin_SD_D0)
+#define MICROPY_HW_SDMMC2_D1                (pyb_pin_SD_D1)
+#define MICROPY_HW_SDMMC2_D2                (pyb_pin_SD_D2)
+#define MICROPY_HW_SDMMC2_D3                (pyb_pin_SD_D3)
+#define MICROPY_HW_SDCARD_DETECT_PIN        (pyb_pin_SD_SW)
+#define MICROPY_HW_SDCARD_DETECT_PULL       (GPIO_PULLUP)
+#define MICROPY_HW_SDCARD_DETECT_PRESENT    (GPIO_PIN_RESET)
+#define MICROPY_HW_SDCARD_MOUNT_AT_BOOT     (0)
+
+// USB config
+#define MICROPY_HW_USB_FS           (1)
+#define MICROPY_HW_USB_HS           (1)
+#define MICROPY_HW_USB_HS_IN_FS     (1)
+#define MICROPY_HW_USB_MAIN_DEV     (USB_PHY_HS_ID)
+
+/******************************************************************************/
+// Bootloader configuration
+
+#define MBOOT_USB_AUTODETECT_PORT   (1)
+#define MBOOT_FSLOAD                (1)
+
+#define MBOOT_I2C_PERIPH_ID         1
+#define MBOOT_I2C_SCL               (pin_B8)
+#define MBOOT_I2C_SDA               (pin_B9)
+#define MBOOT_I2C_ALTFUNC           (4)
+
+#define MBOOT_SPIFLASH_ADDR         (0x80000000)
+#define MBOOT_SPIFLASH_BYTE_SIZE    (64 * 32 * 1024)
+#define MBOOT_SPIFLASH_LAYOUT       "/0x80000000/64*32Kg"
+#define MBOOT_SPIFLASH_ERASE_BLOCKS_PER_PAGE (32 / 4)
+#define MBOOT_SPIFLASH_SPIFLASH     (&spi_bdev.spiflash)
+#define MBOOT_SPIFLASH_CONFIG       (&spiflash_config)
+
+#define MBOOT_SPIFLASH2_ADDR        (0x90000000)
+#define MBOOT_SPIFLASH2_BYTE_SIZE   (64 * 32 * 1024)
+#define MBOOT_SPIFLASH2_LAYOUT      "/0x90000000/64*32Kg"
+#define MBOOT_SPIFLASH2_ERASE_BLOCKS_PER_PAGE (32 / 4)
+#define MBOOT_SPIFLASH2_SPIFLASH    (&spi_bdev2.spiflash)
+#define MBOOT_SPIFLASH2_CONFIG      (&spiflash2_config)
+
+#define MBOOT_BOARD_EARLY_INIT mboot_board_early_init
+void mboot_board_early_init(void);
diff --git a/ports/stm32/boards/PYBD_SF2/mpconfigboard.mk b/ports/stm32/boards/PYBD_SF2/mpconfigboard.mk
new file mode 100644
index 000000000..87e397065
--- /dev/null
+++ b/ports/stm32/boards/PYBD_SF2/mpconfigboard.mk
@@ -0,0 +1,10 @@
+# MCU settings
+MCU_SERIES = f7
+CMSIS_MCU = STM32F722xx
+MICROPY_FLOAT_IMPL = single
+AF_FILE = boards/stm32f722_af.csv
+LD_FILES = boards/PYBD_SF2/f722_qspi.ld
+TEXT0_ADDR = 0x08008000
+
+# MicroPython settings
+MICROPY_PY_LWIP = 1
diff --git a/ports/stm32/boards/PYBD_SF2/pins.csv b/ports/stm32/boards/PYBD_SF2/pins.csv
new file mode 100644
index 000000000..c11f3fe90
--- /dev/null
+++ b/ports/stm32/boards/PYBD_SF2/pins.csv
@@ -0,0 +1,189 @@
+W3,PE3
+W5,PA11
+W5B,PI0
+W6,PA5
+W7,PA4
+W7B,PG7
+W8,PB11
+W9,PA12
+W9B,PI1
+W10,PA6
+W11,PA3
+W12,PB10
+W14,PA7
+W15,PA2
+W16,PA15
+W17,PA1
+W18,PD3
+W19,PA0
+W20,PD0
+W21,PC14
+W22,PE12
+W22B,PF6
+W22C,PF7
+W22D,PF10
+W23,PE1
+W24,PC1
+W25,PE0
+W26,PC13
+W27,PA8
+W27B,PC6
+W28,PE6
+W29,PB3
+W30,PE5
+W32,PE4
+W33,PH2
+W34,PH3
+W43,PB0
+W43B,PC0
+W43C,PF9
+W43D,PF11
+W45,PB12
+W45B,PE14
+W45C,PH8
+W46,PB5
+W47,PC5
+W47B,PF14
+W49,PB13
+W50,PB4
+W51,PC4
+W51B,PF15
+W52,PA10
+W53,PC2
+W53B,PF8
+W54,PA9
+W55,PB9
+W56,PA14
+W57,PC3
+W57B,PF13
+W58,PG11
+W59,PB8
+W60,PG12
+W61,PB7
+W62,PD7
+W63,PB1
+W63B,PD9
+W64,PD6
+W65,PD8
+W66,PG9
+W67,PA13
+W68,PG10
+W70,PB14
+W71,PE15
+W72,PB15
+W73,PH6
+W74,PH7
+X1,PA0
+X2,PA1
+X3,PA2
+X4,PA3
+X5,PA4
+X5B,PG7
+X6,PA5
+X7,PA6
+X8,PA7
+X9,PB8
+X10,PB9
+X11,PC4
+X11B,PF15
+X12,PC5
+X12B,PF14
+Y1,PA9
+Y2,PA10
+Y3,PB4
+Y4,PB5
+Y5,PB12
+Y5B,PE14
+Y5C,PH8
+Y6,PB13
+Y7,PC2
+Y7B,PF8
+Y8,PC3
+Y8B,PF13
+Y9,PB10
+Y10,PB11
+Y11,PB0
+Y11B,PC0
+Y11C,PF9
+Y11D,PF11
+Y12,PB1
+Y12B,PD9
+EN_3V3,PF2
+PULL_SCL,PF1
+PULL_SDA,PH5
+LED_RED,PF3
+LED_GREEN,PF4
+LED_BLUE,PF5
+USR,PA13
+USB_DM,PA11
+USB_DP,PA12
+USB_HS_DM,PB14
+USB_HS_DP,PB15
+-QSPI1_CS,PE13
+-QSPI1_CLK,PE11
+-QSPI1_D0,PE7
+-QSPI1_D1,PE8
+-QSPI1_D2,PE9
+-QSPI1_D3,PE10
+-QSPI2_CS,PB6
+-QSPI2_CLK,PB2
+-QSPI2_D0,PD11
+-QSPI2_D1,PD12
+-QSPI2_D2,PE2
+-QSPI2_D3,PD13
+-SD_D0,PG9
+-SD_D1,PG10
+-SD_D2,PG11
+-SD_D3,PG12
+-SD_CMD,PD7
+-SD_CK,PD6
+SD_SW,PA14
+-WL_REG_ON,PD4
+-WL_HOST_WAKE,PI8
+-WL_RFSW_VDD,PI9
+-WL_GPIO_1,PI11
+-WL_GPIO_2,PI7
+-WL_GPIO_4,PI9
+-WL_SDIO_0,PC8
+-WL_SDIO_1,PC9
+-WL_SDIO_2,PC10
+-WL_SDIO_3,PC11
+-WL_SDIO_CMD,PD2
+-WL_SDIO_CLK,PC12
+-BT_RXD,PC7
+-BT_TXD,PG14
+-BT_CTS,PG13
+-BT_RTS,PG8
+-BT_GPIO_3,PG15
+-BT_GPIO_4,PI5
+-BT_GPIO_5,PI4
+-BT_PCM_SYNC,PE4
+-BT_PCM_IN,PE6
+-BT_PCM_OUT,PE3
+-BT_PCM_CLK,PE5
+-BT_I2C_D0,PI10
+-BT_REG_ON,PI6
+-BT_HOST_WAKE,PD10
+-BT_DEV_WAKE,PD5
+,PD1
+,PD14
+,PD15
+,PF0
+,PF12
+,PG0
+,PG1
+,PG2
+,PG3
+,PG4
+,PG5
+,PG6
+,PH4
+,PH9
+,PH10
+,PH11
+,PH12
+,PH13
+,PH14
+,PH15
+,PI2
+,PI3
diff --git a/ports/stm32/boards/PYBD_SF2/stm32f7xx_hal_conf.h b/ports/stm32/boards/PYBD_SF2/stm32f7xx_hal_conf.h
new file mode 100644
index 000000000..c820dafc4
--- /dev/null
+++ b/ports/stm32/boards/PYBD_SF2/stm32f7xx_hal_conf.h
@@ -0,0 +1,88 @@
+/*
+ * This file is part of the MicroPython project, http://micropython.org/
+ *
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2019 Damien P. George
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+#ifndef MICROPY_INCLUDED_STM32F7XX_HAL_CONF_H
+#define MICROPY_INCLUDED_STM32F7XX_HAL_CONF_H
+
+// Include various HAL modules for convenience
+#include "stm32f7xx_hal_dma.h"
+#include "stm32f7xx_hal_adc.h"
+#include "stm32f7xx_hal_can.h"
+#include "stm32f7xx_hal_cortex.h"
+#include "stm32f7xx_hal_dac.h"
+#include "stm32f7xx_hal_flash.h"
+#include "stm32f7xx_hal_gpio.h"
+#include "stm32f7xx_hal_i2c.h"
+#include "stm32f7xx_hal_mmc.h"
+#include "stm32f7xx_hal_pcd.h"
+#include "stm32f7xx_hal_pwr.h"
+#include "stm32f7xx_hal_rcc.h"
+#include "stm32f7xx_hal_rtc.h"
+#include "stm32f7xx_hal_sd.h"
+#include "stm32f7xx_hal_spi.h"
+#include "stm32f7xx_hal_tim.h"
+#include "stm32f7xx_hal_uart.h"
+
+// Enable various HAL modules
+#define HAL_MODULE_ENABLED
+#define HAL_ADC_MODULE_ENABLED
+#define HAL_CAN_MODULE_ENABLED
+#define HAL_CORTEX_MODULE_ENABLED
+#define HAL_DAC_MODULE_ENABLED
+#define HAL_DMA_MODULE_ENABLED
+#define HAL_FLASH_MODULE_ENABLED
+#define HAL_GPIO_MODULE_ENABLED
+#define HAL_I2C_MODULE_ENABLED
+#define HAL_MMC_MODULE_ENABLED
+#define HAL_PCD_MODULE_ENABLED
+#define HAL_PWR_MODULE_ENABLED
+#define HAL_RCC_MODULE_ENABLED
+#define HAL_RTC_MODULE_ENABLED
+#define HAL_SD_MODULE_ENABLED
+#define HAL_SPI_MODULE_ENABLED
+#define HAL_TIM_MODULE_ENABLED
+#define HAL_UART_MODULE_ENABLED
+
+// Oscillator values in Hz
+#define HSI_VALUE (16000000)
+#define HSE_VALUE ((uint32_t)25000000)
+#define LSI_VALUE (32000)
+#define LSE_VALUE (32768)
+#define EXTERNAL_CLOCK_VALUE (12288000)
+
+// Oscillator timeouts in ms
+#define HSE_STARTUP_TIMEOUT (5000)
+#define LSE_STARTUP_TIMEOUT (5000)
+
+// SysTick has the highest priority
+#define TICK_INT_PRIORITY (0x00)
+
+// No RTOS is used
+#define USE_RTOS 0
+
+// HAL parameter assertions are disabled
+#define assert_param(expr) ((void)0)
+
+#endif // MICROPY_INCLUDED_STM32F7XX_HAL_CONF_H
diff --git a/ports/stm32/boards/PYBD_SF3/bdev.c b/ports/stm32/boards/PYBD_SF3/bdev.c
new file mode 100644
index 000000000..b43028c06
--- /dev/null
+++ b/ports/stm32/boards/PYBD_SF3/bdev.c
@@ -0,0 +1 @@
+#include "boards/PYBD_SF2/bdev.c"
diff --git a/ports/stm32/boards/PYBD_SF3/board_init.c b/ports/stm32/boards/PYBD_SF3/board_init.c
new file mode 100644
index 000000000..c7a9f2800
--- /dev/null
+++ b/ports/stm32/boards/PYBD_SF3/board_init.c
@@ -0,0 +1 @@
+#include "boards/PYBD_SF2/board_init.c"
diff --git a/ports/stm32/boards/PYBD_SF3/mpconfigboard.h b/ports/stm32/boards/PYBD_SF3/mpconfigboard.h
new file mode 100644
index 000000000..8c79e6fe6
--- /dev/null
+++ b/ports/stm32/boards/PYBD_SF3/mpconfigboard.h
@@ -0,0 +1,34 @@
+/*
+ * This file is part of the MicroPython project, http://micropython.org/
+ *
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2018-2019 Damien P. George
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+// Take PYBD_SF2 as base configuration
+#include "boards/PYBD_SF2/mpconfigboard.h"
+
+#undef MICROPY_HW_BOARD_NAME
+#undef MICROPY_HW_MCU_NAME
+
+#define MICROPY_HW_BOARD_NAME       "PYBD-SF3W"
+#define MICROPY_HW_MCU_NAME         "STM32F733IEK"
diff --git a/ports/stm32/boards/PYBD_SF3/mpconfigboard.mk b/ports/stm32/boards/PYBD_SF3/mpconfigboard.mk
new file mode 100644
index 000000000..6104ed247
--- /dev/null
+++ b/ports/stm32/boards/PYBD_SF3/mpconfigboard.mk
@@ -0,0 +1,13 @@
+# MCU settings
+MCU_SERIES = f7
+CMSIS_MCU = STM32F733xx
+MICROPY_FLOAT_IMPL = single
+AF_FILE = boards/stm32f722_af.csv
+LD_FILES = boards/PYBD_SF2/f722_qspi.ld
+TEXT0_ADDR = 0x08008000
+TEXT1_ADDR = 0x90000000
+TEXT0_SECTIONS = .isr_vector .text .data
+TEXT1_SECTIONS = .text_ext
+
+# MicroPython settings
+MICROPY_PY_LWIP = 1
diff --git a/ports/stm32/boards/PYBD_SF3/pins.csv b/ports/stm32/boards/PYBD_SF3/pins.csv
new file mode 100644
index 000000000..c11f3fe90
--- /dev/null
+++ b/ports/stm32/boards/PYBD_SF3/pins.csv
@@ -0,0 +1,189 @@
+W3,PE3
+W5,PA11
+W5B,PI0
+W6,PA5
+W7,PA4
+W7B,PG7
+W8,PB11
+W9,PA12
+W9B,PI1
+W10,PA6
+W11,PA3
+W12,PB10
+W14,PA7
+W15,PA2
+W16,PA15
+W17,PA1
+W18,PD3
+W19,PA0
+W20,PD0
+W21,PC14
+W22,PE12
+W22B,PF6
+W22C,PF7
+W22D,PF10
+W23,PE1
+W24,PC1
+W25,PE0
+W26,PC13
+W27,PA8
+W27B,PC6
+W28,PE6
+W29,PB3
+W30,PE5
+W32,PE4
+W33,PH2
+W34,PH3
+W43,PB0
+W43B,PC0
+W43C,PF9
+W43D,PF11
+W45,PB12
+W45B,PE14
+W45C,PH8
+W46,PB5
+W47,PC5
+W47B,PF14
+W49,PB13
+W50,PB4
+W51,PC4
+W51B,PF15
+W52,PA10
+W53,PC2
+W53B,PF8
+W54,PA9
+W55,PB9
+W56,PA14
+W57,PC3
+W57B,PF13
+W58,PG11
+W59,PB8
+W60,PG12
+W61,PB7
+W62,PD7
+W63,PB1
+W63B,PD9
+W64,PD6
+W65,PD8
+W66,PG9
+W67,PA13
+W68,PG10
+W70,PB14
+W71,PE15
+W72,PB15
+W73,PH6
+W74,PH7
+X1,PA0
+X2,PA1
+X3,PA2
+X4,PA3
+X5,PA4
+X5B,PG7
+X6,PA5
+X7,PA6
+X8,PA7
+X9,PB8
+X10,PB9
+X11,PC4
+X11B,PF15
+X12,PC5
+X12B,PF14
+Y1,PA9
+Y2,PA10
+Y3,PB4
+Y4,PB5
+Y5,PB12
+Y5B,PE14
+Y5C,PH8
+Y6,PB13
+Y7,PC2
+Y7B,PF8
+Y8,PC3
+Y8B,PF13
+Y9,PB10
+Y10,PB11
+Y11,PB0
+Y11B,PC0
+Y11C,PF9
+Y11D,PF11
+Y12,PB1
+Y12B,PD9
+EN_3V3,PF2
+PULL_SCL,PF1
+PULL_SDA,PH5
+LED_RED,PF3
+LED_GREEN,PF4
+LED_BLUE,PF5
+USR,PA13
+USB_DM,PA11
+USB_DP,PA12
+USB_HS_DM,PB14
+USB_HS_DP,PB15
+-QSPI1_CS,PE13
+-QSPI1_CLK,PE11
+-QSPI1_D0,PE7
+-QSPI1_D1,PE8
+-QSPI1_D2,PE9
+-QSPI1_D3,PE10
+-QSPI2_CS,PB6
+-QSPI2_CLK,PB2
+-QSPI2_D0,PD11
+-QSPI2_D1,PD12
+-QSPI2_D2,PE2
+-QSPI2_D3,PD13
+-SD_D0,PG9
+-SD_D1,PG10
+-SD_D2,PG11
+-SD_D3,PG12
+-SD_CMD,PD7
+-SD_CK,PD6
+SD_SW,PA14
+-WL_REG_ON,PD4
+-WL_HOST_WAKE,PI8
+-WL_RFSW_VDD,PI9
+-WL_GPIO_1,PI11
+-WL_GPIO_2,PI7
+-WL_GPIO_4,PI9
+-WL_SDIO_0,PC8
+-WL_SDIO_1,PC9
+-WL_SDIO_2,PC10
+-WL_SDIO_3,PC11
+-WL_SDIO_CMD,PD2
+-WL_SDIO_CLK,PC12
+-BT_RXD,PC7
+-BT_TXD,PG14
+-BT_CTS,PG13
+-BT_RTS,PG8
+-BT_GPIO_3,PG15
+-BT_GPIO_4,PI5
+-BT_GPIO_5,PI4
+-BT_PCM_SYNC,PE4
+-BT_PCM_IN,PE6
+-BT_PCM_OUT,PE3
+-BT_PCM_CLK,PE5
+-BT_I2C_D0,PI10
+-BT_REG_ON,PI6
+-BT_HOST_WAKE,PD10
+-BT_DEV_WAKE,PD5
+,PD1
+,PD14
+,PD15
+,PF0
+,PF12
+,PG0
+,PG1
+,PG2
+,PG3
+,PG4
+,PG5
+,PG6
+,PH4
+,PH9
+,PH10
+,PH11
+,PH12
+,PH13
+,PH14
+,PH15
+,PI2
+,PI3
diff --git a/ports/stm32/boards/PYBD_SF3/stm32f7xx_hal_conf.h b/ports/stm32/boards/PYBD_SF3/stm32f7xx_hal_conf.h
new file mode 100644
index 000000000..0f178c2ba
--- /dev/null
+++ b/ports/stm32/boards/PYBD_SF3/stm32f7xx_hal_conf.h
@@ -0,0 +1 @@
+#include "boards/PYBD_SF2/stm32f7xx_hal_conf.h"
diff --git a/ports/stm32/boards/PYBD_SF6/bdev.c b/ports/stm32/boards/PYBD_SF6/bdev.c
new file mode 100644
index 000000000..b43028c06
--- /dev/null
+++ b/ports/stm32/boards/PYBD_SF6/bdev.c
@@ -0,0 +1 @@
+#include "boards/PYBD_SF2/bdev.c"
diff --git a/ports/stm32/boards/PYBD_SF6/board_init.c b/ports/stm32/boards/PYBD_SF6/board_init.c
new file mode 100644
index 000000000..c7a9f2800
--- /dev/null
+++ b/ports/stm32/boards/PYBD_SF6/board_init.c
@@ -0,0 +1 @@
+#include "boards/PYBD_SF2/board_init.c"
diff --git a/ports/stm32/boards/PYBD_SF6/f767.ld b/ports/stm32/boards/PYBD_SF6/f767.ld
new file mode 100644
index 000000000..d910438a7
--- /dev/null
+++ b/ports/stm32/boards/PYBD_SF6/f767.ld
@@ -0,0 +1,96 @@
+/*
+    Linker script for PYBD with STM32F767
+
+    Memory layout for mboot configuration (this here describes the app part):
+
+    FLASH_APP   .isr_vector
+    FLASH_APP   .text
+    FLASH_APP   .data
+
+    RAM         .data
+    RAM         .bss
+    RAM         .heap
+    RAM         .stack
+*/
+
+/* Specify the memory areas */
+MEMORY
+{
+    FLASH (rx)      : ORIGIN = 0x08000000, LENGTH = 2048K
+    FLASH_ISR (rx)  : ORIGIN = 0x08000000, LENGTH = 32K     /* sector 0, 32K */
+    FLASH_APP (rx)  : ORIGIN = 0x08008000, LENGTH = 2016K   /* sectors 1-11 3x32K 1*128K 7*256K */
+    FLASH_EXT (rx)  : ORIGIN = 0x90000000, LENGTH = 2048K   /* external QSPI */
+    RAM (rwx)       : ORIGIN = 0x20000000, LENGTH = 512K    /* DTCM=128k, SRAM1=368K, SRAM2=16K */
+}
+
+/* produce a link error if there is not this amount of RAM for these sections */
+_minimum_stack_size = 2K;
+_minimum_heap_size = 16K;
+
+/* Define tho top end of the stack.  The stack is full descending so begins just
+   above last byte of RAM.  Note that EABI requires the stack to be 8-byte
+   aligned for a call. */
+_estack = ORIGIN(RAM) + LENGTH(RAM);
+
+/* RAM extents for the garbage collector */
+_ram_start = ORIGIN(RAM);
+_ram_end = ORIGIN(RAM) + LENGTH(RAM);
+_heap_start = _ebss; /* heap starts just after statically allocated memory */
+_heap_end = _ram_end - 24K; /* 24k stack */
+
+ENTRY(Reset_Handler)
+
+/* Define output sections */
+SECTIONS
+{
+    .isr_vector :
+    {
+        . = ALIGN(4);
+        KEEP(*(.isr_vector))
+        . = ALIGN(4);
+    } >FLASH_APP
+
+    .text :
+    {
+        . = ALIGN(4);
+        *(.text*)
+        *(.rodata*)
+        . = ALIGN(4);
+        _etext = .;
+    } >FLASH_APP
+
+    _sidata = LOADADDR(.data);
+
+    .data :
+    {
+        . = ALIGN(4);
+        _sdata = .;
+        *(.data*)
+        . = ALIGN(4);
+        _edata = .;
+    } >RAM AT> FLASH_APP
+
+    .bss :
+    {
+        . = ALIGN(4);
+        _sbss = .;
+        *(.bss*)
+        *(COMMON)
+        . = ALIGN(4);
+        _ebss = .;
+    } >RAM
+
+    .heap :
+    {
+        . = ALIGN(4);
+        . = . + _minimum_heap_size;
+        . = ALIGN(4);
+    } >RAM
+
+    .stack :
+    {
+        . = ALIGN(4);
+        . = . + _minimum_stack_size;
+        . = ALIGN(4);
+    } >RAM
+}
diff --git a/ports/stm32/boards/PYBD_SF6/mpconfigboard.h b/ports/stm32/boards/PYBD_SF6/mpconfigboard.h
new file mode 100644
index 000000000..cbfbe3994
--- /dev/null
+++ b/ports/stm32/boards/PYBD_SF6/mpconfigboard.h
@@ -0,0 +1,66 @@
+/*
+ * This file is part of the MicroPython project, http://micropython.org/
+ *
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2018-2019 Damien P. George
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+// Take PYBD_SF2 as base configuration
+#include "boards/PYBD_SF2/mpconfigboard.h"
+
+#undef MICROPY_HW_BOARD_NAME
+#undef MICROPY_HW_MCU_NAME
+#undef MICROPY_HW_CLK_PLLM
+#undef MICROPY_HW_CLK_PLLN
+#undef MICROPY_HW_CLK_PLLP
+#undef MICROPY_HW_CLK_PLLQ
+#undef MICROPY_HW_FLASH_LATENCY
+
+#define MICROPY_HW_BOARD_NAME       "PYBD-SF6W"
+#define MICROPY_HW_MCU_NAME         "STM32F767IIK"
+
+// HSE is 25MHz, run SYS at 144MHz
+#define MICROPY_HW_CLK_PLLM         (25)
+#define MICROPY_HW_CLK_PLLN         (288)
+#define MICROPY_HW_CLK_PLLP         (RCC_PLLP_DIV2)
+#define MICROPY_HW_CLK_PLLQ         (6)
+#define MICROPY_HW_FLASH_LATENCY    (FLASH_LATENCY_4)
+
+// Extra UART config
+#define MICROPY_HW_UART7_TX         (pyb_pin_W16)
+#define MICROPY_HW_UART7_RX         (pyb_pin_W22B)
+
+// Extra CAN busses
+#define MICROPY_HW_CAN2_NAME        "Y"
+#define MICROPY_HW_CAN2_TX          (pyb_pin_Y6)
+#define MICROPY_HW_CAN2_RX          (pyb_pin_Y5)
+
+// Ethernet via RMII
+#define MICROPY_HW_ETH_MDC          (pyb_pin_W24)
+#define MICROPY_HW_ETH_MDIO         (pyb_pin_W15)
+#define MICROPY_HW_ETH_RMII_REF_CLK (pyb_pin_W17)
+#define MICROPY_HW_ETH_RMII_CRS_DV  (pyb_pin_W14)
+#define MICROPY_HW_ETH_RMII_RXD0    (pyb_pin_W51)
+#define MICROPY_HW_ETH_RMII_RXD1    (pyb_pin_W47)
+#define MICROPY_HW_ETH_RMII_TX_EN   (pyb_pin_W8)
+#define MICROPY_HW_ETH_RMII_TXD0    (pyb_pin_W45)
+#define MICROPY_HW_ETH_RMII_TXD1    (pyb_pin_W49)
diff --git a/ports/stm32/boards/PYBD_SF6/mpconfigboard.mk b/ports/stm32/boards/PYBD_SF6/mpconfigboard.mk
new file mode 100644
index 000000000..0288b9142
--- /dev/null
+++ b/ports/stm32/boards/PYBD_SF6/mpconfigboard.mk
@@ -0,0 +1,10 @@
+# MCU settings
+MCU_SERIES = f7
+CMSIS_MCU = STM32F767xx
+MICROPY_FLOAT_IMPL = double
+AF_FILE = boards/stm32f767_af.csv
+LD_FILES = boards/PYBD_SF6/f767.ld
+TEXT0_ADDR = 0x08008000
+
+# MicroPython settings
+MICROPY_PY_LWIP = 1
diff --git a/ports/stm32/boards/PYBD_SF6/pins.csv b/ports/stm32/boards/PYBD_SF6/pins.csv
new file mode 100644
index 000000000..c11f3fe90
--- /dev/null
+++ b/ports/stm32/boards/PYBD_SF6/pins.csv
@@ -0,0 +1,189 @@
+W3,PE3
+W5,PA11
+W5B,PI0
+W6,PA5
+W7,PA4
+W7B,PG7
+W8,PB11
+W9,PA12
+W9B,PI1
+W10,PA6
+W11,PA3
+W12,PB10
+W14,PA7
+W15,PA2
+W16,PA15
+W17,PA1
+W18,PD3
+W19,PA0
+W20,PD0
+W21,PC14
+W22,PE12
+W22B,PF6
+W22C,PF7
+W22D,PF10
+W23,PE1
+W24,PC1
+W25,PE0
+W26,PC13
+W27,PA8
+W27B,PC6
+W28,PE6
+W29,PB3
+W30,PE5
+W32,PE4
+W33,PH2
+W34,PH3
+W43,PB0
+W43B,PC0
+W43C,PF9
+W43D,PF11
+W45,PB12
+W45B,PE14
+W45C,PH8
+W46,PB5
+W47,PC5
+W47B,PF14
+W49,PB13
+W50,PB4
+W51,PC4
+W51B,PF15
+W52,PA10
+W53,PC2
+W53B,PF8
+W54,PA9
+W55,PB9
+W56,PA14
+W57,PC3
+W57B,PF13
+W58,PG11
+W59,PB8
+W60,PG12
+W61,PB7
+W62,PD7
+W63,PB1
+W63B,PD9
+W64,PD6
+W65,PD8
+W66,PG9
+W67,PA13
+W68,PG10
+W70,PB14
+W71,PE15
+W72,PB15
+W73,PH6
+W74,PH7
+X1,PA0
+X2,PA1
+X3,PA2
+X4,PA3
+X5,PA4
+X5B,PG7
+X6,PA5
+X7,PA6
+X8,PA7
+X9,PB8
+X10,PB9
+X11,PC4
+X11B,PF15
+X12,PC5
+X12B,PF14
+Y1,PA9
+Y2,PA10
+Y3,PB4
+Y4,PB5
+Y5,PB12
+Y5B,PE14
+Y5C,PH8
+Y6,PB13
+Y7,PC2
+Y7B,PF8
+Y8,PC3
+Y8B,PF13
+Y9,PB10
+Y10,PB11
+Y11,PB0
+Y11B,PC0
+Y11C,PF9
+Y11D,PF11
+Y12,PB1
+Y12B,PD9
+EN_3V3,PF2
+PULL_SCL,PF1
+PULL_SDA,PH5
+LED_RED,PF3
+LED_GREEN,PF4
+LED_BLUE,PF5
+USR,PA13
+USB_DM,PA11
+USB_DP,PA12
+USB_HS_DM,PB14
+USB_HS_DP,PB15
+-QSPI1_CS,PE13
+-QSPI1_CLK,PE11
+-QSPI1_D0,PE7
+-QSPI1_D1,PE8
+-QSPI1_D2,PE9
+-QSPI1_D3,PE10
+-QSPI2_CS,PB6
+-QSPI2_CLK,PB2
+-QSPI2_D0,PD11
+-QSPI2_D1,PD12
+-QSPI2_D2,PE2
+-QSPI2_D3,PD13
+-SD_D0,PG9
+-SD_D1,PG10
+-SD_D2,PG11
+-SD_D3,PG12
+-SD_CMD,PD7
+-SD_CK,PD6
+SD_SW,PA14
+-WL_REG_ON,PD4
+-WL_HOST_WAKE,PI8
+-WL_RFSW_VDD,PI9
+-WL_GPIO_1,PI11
+-WL_GPIO_2,PI7
+-WL_GPIO_4,PI9
+-WL_SDIO_0,PC8
+-WL_SDIO_1,PC9
+-WL_SDIO_2,PC10
+-WL_SDIO_3,PC11
+-WL_SDIO_CMD,PD2
+-WL_SDIO_CLK,PC12
+-BT_RXD,PC7
+-BT_TXD,PG14
+-BT_CTS,PG13
+-BT_RTS,PG8
+-BT_GPIO_3,PG15
+-BT_GPIO_4,PI5
+-BT_GPIO_5,PI4
+-BT_PCM_SYNC,PE4
+-BT_PCM_IN,PE6
+-BT_PCM_OUT,PE3
+-BT_PCM_CLK,PE5
+-BT_I2C_D0,PI10
+-BT_REG_ON,PI6
+-BT_HOST_WAKE,PD10
+-BT_DEV_WAKE,PD5
+,PD1
+,PD14
+,PD15
+,PF0
+,PF12
+,PG0
+,PG1
+,PG2
+,PG3
+,PG4
+,PG5
+,PG6
+,PH4
+,PH9
+,PH10
+,PH11
+,PH12
+,PH13
+,PH14
+,PH15
+,PI2
+,PI3
diff --git a/ports/stm32/boards/PYBD_SF6/stm32f7xx_hal_conf.h b/ports/stm32/boards/PYBD_SF6/stm32f7xx_hal_conf.h
new file mode 100644
index 000000000..0f178c2ba
--- /dev/null
+++ b/ports/stm32/boards/PYBD_SF6/stm32f7xx_hal_conf.h
@@ -0,0 +1 @@
+#include "boards/PYBD_SF2/stm32f7xx_hal_conf.h"
-- 
GitLab