diff --git a/ports/stm32f4/Makefile b/ports/stm32f4/Makefile
index 2727ea954f..3943944ccb 100755
--- a/ports/stm32f4/Makefile
+++ b/ports/stm32f4/Makefile
@@ -22,7 +22,7 @@
# 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.
-DEBUG = 1
+#DEBUG = 1
# Select the board to build for.
ifeq ($(BOARD),)
diff --git a/ports/stm32f4/boards/STM32F401.ld b/ports/stm32f4/boards/STM32F401.ld
new file mode 100644
index 0000000000..b3d772a784
--- /dev/null
+++ b/ports/stm32f4/boards/STM32F401.ld
@@ -0,0 +1,106 @@
+/*
+ GNU linker script for STM32F401 with bootloader (such as the Meowbit)
+*/
+
+/* Specify the memory areas */
+MEMORY
+{
+ FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 512K - 64K /* entire flash, sans bootloader */
+ FLASH_ISR (rx) : ORIGIN = 0x08000000, LENGTH = 64K /* sector 4, 0-3 used by bootloader*/
+ FLASH_TEXT (rx) : ORIGIN = 0x08010000, LENGTH = 384K /* sector 4 is 64K, sectors 5,6,7 are 128K */
+ RAM (xrw) : ORIGIN = 0x20000194, LENGTH = 96K - 0x194 /* more bootloader schnenaigans */
+}
+
+/* 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);
+
+ENTRY(Reset_Handler)
+
+/* define output sections */
+SECTIONS
+{
+ /* The startup code goes first into FLASH */
+ .isr_vector :
+ {
+ . = ALIGN(4);
+ KEEP(*(.isr_vector)) /* Startup code */
+
+ /* This first flash block is 16K annd the isr vectors only take up
+ about 400 bytes. Micropython pads this with files, but this didn't
+ work with the size of Circuitpython's ff object. */
+
+ . = ALIGN(4);
+ } >FLASH_ISR
+
+ /* The program code and other data goes into FLASH */
+ .text :
+ {
+ . = ALIGN(4);
+ *(.text*) /* .text* sections (code) */
+ *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
+ /* *(.glue_7) */ /* glue arm to thumb code */
+ /* *(.glue_7t) */ /* glue thumb to arm code */
+
+ . = ALIGN(4);
+ _etext = .; /* define a global symbol at end of code */
+ } >FLASH_TEXT
+
+ /* used by the startup to initialize data */
+ _sidata = LOADADDR(.data);
+
+ /* This is the initialized data section
+ The program executes knowing that the data is in the RAM
+ but the loader puts the initial values in the FLASH (inidata).
+ It is one task of the startup to copy the initial values from FLASH to RAM. */
+ .data :
+ {
+ . = ALIGN(4);
+ _sdata = .; /* create a global symbol at data start; used by startup code in order to initialise the .data section in RAM */
+ *(.data*) /* .data* sections */
+
+ . = ALIGN(4);
+ _edata = .; /* define a global symbol at data end; used by startup code in order to initialise the .data section in RAM */
+ } >RAM AT> FLASH_TEXT
+
+ /* Uninitialized data section */
+ .bss :
+ {
+ . = ALIGN(4);
+ _sbss = .; /* define a global symbol at bss start; used by startup code */
+ *(.bss*)
+ *(COMMON)
+
+ . = ALIGN(4);
+ _ebss = .; /* define a global symbol at bss end; used by startup code and GC */
+ } >RAM
+
+ /* this is to define the start of the heap, and make sure we have a minimum size */
+ .heap :
+ {
+ . = ALIGN(4);
+ . = . + _minimum_heap_size;
+ . = ALIGN(4);
+ } >RAM
+
+ /* this just checks there is enough RAM for the stack */
+ .stack :
+ {
+ . = ALIGN(4);
+ . = . + _minimum_stack_size;
+ . = ALIGN(4);
+ } >RAM
+
+ .ARM.attributes 0 : { *(.ARM.attributes) }
+}
+
+
diff --git a/ports/stm32f4/boards/STM32F401_boot.ld b/ports/stm32f4/boards/STM32F401_boot.ld
new file mode 100644
index 0000000000..7f582fdf9f
--- /dev/null
+++ b/ports/stm32f4/boards/STM32F401_boot.ld
@@ -0,0 +1,106 @@
+/*
+ GNU linker script for STM32F401 with bootloader (such as the Meowbit)
+*/
+
+/* Specify the memory areas */
+MEMORY
+{
+ FLASH (rx) : ORIGIN = 0x08010000, LENGTH = 512K - 64K /* entire flash, sans bootloader */
+ FLASH_ISR (rx) : ORIGIN = 0x08010000, LENGTH = 64K /* sector 4, 0-3 used by bootloader*/
+ FLASH_TEXT (rx) : ORIGIN = 0x08020000, LENGTH = 384K /* sector 4 is 64K, sectors 5,6,7 are 128K */
+ RAM (xrw) : ORIGIN = 0x20000194, LENGTH = 96K - 0x194 /* more bootloader schnenaigans */
+}
+
+/* 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);
+
+ENTRY(Reset_Handler)
+
+/* define output sections */
+SECTIONS
+{
+ /* The startup code goes first into FLASH */
+ .isr_vector :
+ {
+ . = ALIGN(4);
+ KEEP(*(.isr_vector)) /* Startup code */
+
+ /* This first flash block is 16K annd the isr vectors only take up
+ about 400 bytes. Micropython pads this with files, but this didn't
+ work with the size of Circuitpython's ff object. */
+
+ . = ALIGN(4);
+ } >FLASH_ISR
+
+ /* The program code and other data goes into FLASH */
+ .text :
+ {
+ . = ALIGN(4);
+ *(.text*) /* .text* sections (code) */
+ *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
+ /* *(.glue_7) */ /* glue arm to thumb code */
+ /* *(.glue_7t) */ /* glue thumb to arm code */
+
+ . = ALIGN(4);
+ _etext = .; /* define a global symbol at end of code */
+ } >FLASH_TEXT
+
+ /* used by the startup to initialize data */
+ _sidata = LOADADDR(.data);
+
+ /* This is the initialized data section
+ The program executes knowing that the data is in the RAM
+ but the loader puts the initial values in the FLASH (inidata).
+ It is one task of the startup to copy the initial values from FLASH to RAM. */
+ .data :
+ {
+ . = ALIGN(4);
+ _sdata = .; /* create a global symbol at data start; used by startup code in order to initialise the .data section in RAM */
+ *(.data*) /* .data* sections */
+
+ . = ALIGN(4);
+ _edata = .; /* define a global symbol at data end; used by startup code in order to initialise the .data section in RAM */
+ } >RAM AT> FLASH_TEXT
+
+ /* Uninitialized data section */
+ .bss :
+ {
+ . = ALIGN(4);
+ _sbss = .; /* define a global symbol at bss start; used by startup code */
+ *(.bss*)
+ *(COMMON)
+
+ . = ALIGN(4);
+ _ebss = .; /* define a global symbol at bss end; used by startup code and GC */
+ } >RAM
+
+ /* this is to define the start of the heap, and make sure we have a minimum size */
+ .heap :
+ {
+ . = ALIGN(4);
+ . = . + _minimum_heap_size;
+ . = ALIGN(4);
+ } >RAM
+
+ /* this just checks there is enough RAM for the stack */
+ .stack :
+ {
+ . = ALIGN(4);
+ . = . + _minimum_stack_size;
+ . = ALIGN(4);
+ } >RAM
+
+ .ARM.attributes 0 : { *(.ARM.attributes) }
+}
+
+
diff --git a/ports/stm32f4/boards/meowbit_v121/mpconfigboard.h b/ports/stm32f4/boards/meowbit_v121/mpconfigboard.h
index b2d53d9999..f2fe3ca804 100644
--- a/ports/stm32f4/boards/meowbit_v121/mpconfigboard.h
+++ b/ports/stm32f4/boards/meowbit_v121/mpconfigboard.h
@@ -29,24 +29,14 @@
#define MICROPY_HW_BOARD_NAME "MEOWBIT"
#define MICROPY_HW_MCU_NAME "STM32F401xE"
-#define FLASH_SIZE (0x100000)
+#define FLASH_SIZE (0x80000)
#define FLASH_PAGE_SIZE (0x4000)
#define AUTORESET_DELAY_MS 500
#define BOARD_FLASH_SIZE (FLASH_SIZE - 0x4000)
// On-board flash
-#define SPI_FLASH_MOSI_PIN &pin_PB05
-#define SPI_FLASH_MISO_PIN &pin_PB04
-#define SPI_FLASH_SCK_PIN &pin_PB03
-#define SPI_FLASH_CS_PIN &pin_PA15
-
-#define DEFAULT_I2C_BUS_SCL (&pin_PB06)
-#define DEFAULT_I2C_BUS_SDA (&pin_PB07)
-
-#define DEFAULT_SPI_BUS_SCK (&pin_PB13)
-#define DEFAULT_SPI_BUS_MOSI (&pin_PB15)
-#define DEFAULT_SPI_BUS_MISO (&pin_PB14)
-
-#define DEFAULT_UART_BUS_RX (&pin_PB11)
-#define DEFAULT_UART_BUS_TX (&pin_PB10)
+#define SPI_FLASH_MOSI_PIN (&pin_PB15)
+#define SPI_FLASH_MISO_PIN (&pin_PB14)
+#define SPI_FLASH_SCK_PIN (&pin_PB13)
+#define SPI_FLASH_CS_PIN (&pin_PB01)
diff --git a/ports/stm32f4/boards/meowbit_v121/mpconfigboard.mk b/ports/stm32f4/boards/meowbit_v121/mpconfigboard.mk
index 7998e04523..8b605975d5 100644
--- a/ports/stm32f4/boards/meowbit_v121/mpconfigboard.mk
+++ b/ports/stm32f4/boards/meowbit_v121/mpconfigboard.mk
@@ -1,12 +1,12 @@
USB_VID = 0x239A
USB_PID = 0x805A
-USB_PRODUCT = "Feather STM32F405 Express"
-USB_MANUFACTURER = "Adafruit Industries LLC"
+USB_PRODUCT = "Meowbit"
+USB_MANUFACTURER = "Kittenbot"
USB_DEVICES = "CDC,MSC"
SPI_FLASH_FILESYSTEM = 1
EXTERNAL_FLASH_DEVICE_COUNT = 1
-EXTERNAL_FLASH_DEVICES = GD25Q16C
+EXTERNAL_FLASH_DEVICES = W25Q16JV_IQ
LONGINT_IMPL = MPZ
MCU_SERIES = m4
@@ -14,6 +14,6 @@ MCU_VARIANT = stm32f4
MCU_SUB_VARIANT = stm32f401xe
MCU_PACKAGE = 64
CMSIS_MCU = STM32F401xE
-LD_FILE = boards/STM32F405.ld
-TEXT0_ADDR = 0x08000000
-TEXT1_ADDR = 0x08010000
\ No newline at end of file
+LD_FILE = boards/STM32F401.ld
+TEXT0_ADDR = 0x08010000
+TEXT1_ADDR = 0x08020000
\ No newline at end of file
diff --git a/ports/stm32f4/boards/meowbit_v121/pins.c b/ports/stm32f4/boards/meowbit_v121/pins.c
index 169fbf2744..dc0003dd15 100644
--- a/ports/stm32f4/boards/meowbit_v121/pins.c
+++ b/ports/stm32f4/boards/meowbit_v121/pins.c
@@ -1,11 +1,7 @@
#include "shared-bindings/board/__init__.h"
STATIC const mp_rom_map_elem_t board_module_globals_table[] = {
- { MP_ROM_QSTR(MP_QSTR_A0), MP_ROM_PTR(&pin_PA04) },
-
-
- { MP_ROM_QSTR(MP_QSTR_I2C), MP_ROM_PTR(&board_i2c_obj) },
- { MP_ROM_QSTR(MP_QSTR_SPI), MP_ROM_PTR(&board_spi_obj) },
- { MP_ROM_QSTR(MP_QSTR_UART), MP_ROM_PTR(&board_uart_obj) },
+ { MP_ROM_QSTR(MP_QSTR_LED_RED), MP_ROM_PTR(&pin_PB04) },
+ { MP_ROM_QSTR(MP_QSTR_LED_GREEN), MP_ROM_PTR(&pin_PB05) }
};
MP_DEFINE_CONST_DICT(board_module_globals, board_module_globals_table);
diff --git a/ports/stm32f4/boards/startup_stm32f401xe.s b/ports/stm32f4/boards/startup_stm32f401xe.s
new file mode 100644
index 0000000000..815ac17197
--- /dev/null
+++ b/ports/stm32f4/boards/startup_stm32f401xe.s
@@ -0,0 +1,448 @@
+/**
+ ******************************************************************************
+ * @file startup_stm32f401xe.s
+ * @author MCD Application Team
+ * @brief STM32F401xExx Devices vector table for GCC based toolchains.
+ * This module performs:
+ * - Set the initial SP
+ * - Set the initial PC == Reset_Handler,
+ * - Set the vector table entries with the exceptions ISR address
+ * - Branches to main in the C library (which eventually
+ * calls main()).
+ * After Reset the Cortex-M4 processor is in Thread mode,
+ * priority is Privileged, and the Stack is set to Main.
+ ******************************************************************************
+ * @attention
+ *
+ *
© COPYRIGHT 2017 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************
+ */
+
+ .syntax unified
+ .cpu cortex-m4
+ .fpu softvfp
+ .thumb
+
+.global g_pfnVectors
+.global Default_Handler
+
+/* start address for the initialization values of the .data section.
+defined in linker script */
+.word _sidata
+/* start address for the .data section. defined in linker script */
+.word _sdata
+/* end address for the .data section. defined in linker script */
+.word _edata
+/* start address for the .bss section. defined in linker script */
+.word _sbss
+/* end address for the .bss section. defined in linker script */
+.word _ebss
+/* stack used for SystemInit_ExtMemCtl; always internal RAM used */
+
+/**
+ * @brief This is the code that gets called when the processor first
+ * starts execution following a reset event. Only the absolutely
+ * necessary set is performed, after which the application
+ * supplied main() routine is called.
+ * @param None
+ * @retval : None
+*/
+
+ .section .text.Reset_Handler
+ .weak Reset_Handler
+ .type Reset_Handler, %function
+Reset_Handler:
+ ldr sp, =_estack /* set stack pointer */
+
+/* Copy the data segment initializers from flash to SRAM */
+ movs r1, #0
+ b LoopCopyDataInit
+
+CopyDataInit:
+ ldr r3, =_sidata
+ ldr r3, [r3, r1]
+ str r3, [r0, r1]
+ adds r1, r1, #4
+
+LoopCopyDataInit:
+ ldr r0, =_sdata
+ ldr r3, =_edata
+ adds r2, r0, r1
+ cmp r2, r3
+ bcc CopyDataInit
+ ldr r2, =_sbss
+ b LoopFillZerobss
+/* Zero fill the bss segment. */
+FillZerobss:
+ movs r3, #0
+ str r3, [r2], #4
+
+LoopFillZerobss:
+ ldr r3, = _ebss
+ cmp r2, r3
+ bcc FillZerobss
+
+/* Call the clock system intitialization function.*/
+ bl SystemInit
+/* Call static constructors */
+ /* bl __libc_init_array */
+/* Call the application's entry point.*/
+ bl main
+ bx lr
+.size Reset_Handler, .-Reset_Handler
+
+/**
+ * @brief This is the code that gets called when the processor receives an
+ * unexpected interrupt. This simply enters an infinite loop, preserving
+ * the system state for examination by a debugger.
+ * @param None
+ * @retval None
+*/
+ .section .text.Default_Handler,"ax",%progbits
+Default_Handler:
+Infinite_Loop:
+ b Infinite_Loop
+ .size Default_Handler, .-Default_Handler
+/******************************************************************************
+*
+* The minimal vector table for a Cortex M3. Note that the proper constructs
+* must be placed on this to ensure that it ends up at physical address
+* 0x0000.0000.
+*
+*******************************************************************************/
+ .section .isr_vector,"a",%progbits
+ .type g_pfnVectors, %object
+ .size g_pfnVectors, .-g_pfnVectors
+
+g_pfnVectors:
+ .word _estack
+ .word Reset_Handler
+ .word NMI_Handler
+ .word HardFault_Handler
+ .word MemManage_Handler
+ .word BusFault_Handler
+ .word UsageFault_Handler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word SVC_Handler
+ .word DebugMon_Handler
+ .word 0
+ .word PendSV_Handler
+ .word SysTick_Handler
+
+ /* External Interrupts */
+ .word WWDG_IRQHandler /* Window WatchDog */
+ .word PVD_IRQHandler /* PVD through EXTI Line detection */
+ .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */
+ .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */
+ .word FLASH_IRQHandler /* FLASH */
+ .word RCC_IRQHandler /* RCC */
+ .word EXTI0_IRQHandler /* EXTI Line0 */
+ .word EXTI1_IRQHandler /* EXTI Line1 */
+ .word EXTI2_IRQHandler /* EXTI Line2 */
+ .word EXTI3_IRQHandler /* EXTI Line3 */
+ .word EXTI4_IRQHandler /* EXTI Line4 */
+ .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */
+ .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */
+ .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */
+ .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */
+ .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */
+ .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */
+ .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */
+ .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word EXTI9_5_IRQHandler /* External Line[9:5]s */
+ .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */
+ .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */
+ .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */
+ .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */
+ .word TIM2_IRQHandler /* TIM2 */
+ .word TIM3_IRQHandler /* TIM3 */
+ .word TIM4_IRQHandler /* TIM4 */
+ .word I2C1_EV_IRQHandler /* I2C1 Event */
+ .word I2C1_ER_IRQHandler /* I2C1 Error */
+ .word I2C2_EV_IRQHandler /* I2C2 Event */
+ .word I2C2_ER_IRQHandler /* I2C2 Error */
+ .word SPI1_IRQHandler /* SPI1 */
+ .word SPI2_IRQHandler /* SPI2 */
+ .word USART1_IRQHandler /* USART1 */
+ .word USART2_IRQHandler /* USART2 */
+ .word 0 /* Reserved */
+ .word EXTI15_10_IRQHandler /* External Line[15:10]s */
+ .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */
+ .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */
+ .word 0 /* Reserved */
+ .word SDIO_IRQHandler /* SDIO */
+ .word TIM5_IRQHandler /* TIM5 */
+ .word SPI3_IRQHandler /* SPI3 */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */
+ .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */
+ .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */
+ .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */
+ .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word OTG_FS_IRQHandler /* USB OTG FS */
+ .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */
+ .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */
+ .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */
+ .word USART6_IRQHandler /* USART6 */
+ .word I2C3_EV_IRQHandler /* I2C3 event */
+ .word I2C3_ER_IRQHandler /* I2C3 error */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word FPU_IRQHandler /* FPU */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word SPI4_IRQHandler /* SPI4 */
+
+/*******************************************************************************
+*
+* Provide weak aliases for each Exception handler to the Default_Handler.
+* As they are weak aliases, any function with the same name will override
+* this definition.
+*
+*******************************************************************************/
+ .weak NMI_Handler
+ .thumb_set NMI_Handler,Default_Handler
+
+ .weak HardFault_Handler
+ .thumb_set HardFault_Handler,Default_Handler
+
+ .weak MemManage_Handler
+ .thumb_set MemManage_Handler,Default_Handler
+
+ .weak BusFault_Handler
+ .thumb_set BusFault_Handler,Default_Handler
+
+ .weak UsageFault_Handler
+ .thumb_set UsageFault_Handler,Default_Handler
+
+ .weak SVC_Handler
+ .thumb_set SVC_Handler,Default_Handler
+
+ .weak DebugMon_Handler
+ .thumb_set DebugMon_Handler,Default_Handler
+
+ .weak PendSV_Handler
+ .thumb_set PendSV_Handler,Default_Handler
+
+ .weak SysTick_Handler
+ .thumb_set SysTick_Handler,Default_Handler
+
+ .weak WWDG_IRQHandler
+ .thumb_set WWDG_IRQHandler,Default_Handler
+
+ .weak PVD_IRQHandler
+ .thumb_set PVD_IRQHandler,Default_Handler
+
+ .weak TAMP_STAMP_IRQHandler
+ .thumb_set TAMP_STAMP_IRQHandler,Default_Handler
+
+ .weak RTC_WKUP_IRQHandler
+ .thumb_set RTC_WKUP_IRQHandler,Default_Handler
+
+ .weak FLASH_IRQHandler
+ .thumb_set FLASH_IRQHandler,Default_Handler
+
+ .weak RCC_IRQHandler
+ .thumb_set RCC_IRQHandler,Default_Handler
+
+ .weak EXTI0_IRQHandler
+ .thumb_set EXTI0_IRQHandler,Default_Handler
+
+ .weak EXTI1_IRQHandler
+ .thumb_set EXTI1_IRQHandler,Default_Handler
+
+ .weak EXTI2_IRQHandler
+ .thumb_set EXTI2_IRQHandler,Default_Handler
+
+ .weak EXTI3_IRQHandler
+ .thumb_set EXTI3_IRQHandler,Default_Handler
+
+ .weak EXTI4_IRQHandler
+ .thumb_set EXTI4_IRQHandler,Default_Handler
+
+ .weak DMA1_Stream0_IRQHandler
+ .thumb_set DMA1_Stream0_IRQHandler,Default_Handler
+
+ .weak DMA1_Stream1_IRQHandler
+ .thumb_set DMA1_Stream1_IRQHandler,Default_Handler
+
+ .weak DMA1_Stream2_IRQHandler
+ .thumb_set DMA1_Stream2_IRQHandler,Default_Handler
+
+ .weak DMA1_Stream3_IRQHandler
+ .thumb_set DMA1_Stream3_IRQHandler,Default_Handler
+
+ .weak DMA1_Stream4_IRQHandler
+ .thumb_set DMA1_Stream4_IRQHandler,Default_Handler
+
+ .weak DMA1_Stream5_IRQHandler
+ .thumb_set DMA1_Stream5_IRQHandler,Default_Handler
+
+ .weak DMA1_Stream6_IRQHandler
+ .thumb_set DMA1_Stream6_IRQHandler,Default_Handler
+
+ .weak ADC_IRQHandler
+ .thumb_set ADC_IRQHandler,Default_Handler
+
+ .weak EXTI9_5_IRQHandler
+ .thumb_set EXTI9_5_IRQHandler,Default_Handler
+
+ .weak TIM1_BRK_TIM9_IRQHandler
+ .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler
+
+ .weak TIM1_UP_TIM10_IRQHandler
+ .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler
+
+ .weak TIM1_TRG_COM_TIM11_IRQHandler
+ .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler
+
+ .weak TIM1_CC_IRQHandler
+ .thumb_set TIM1_CC_IRQHandler,Default_Handler
+
+ .weak TIM2_IRQHandler
+ .thumb_set TIM2_IRQHandler,Default_Handler
+
+ .weak TIM3_IRQHandler
+ .thumb_set TIM3_IRQHandler,Default_Handler
+
+ .weak TIM4_IRQHandler
+ .thumb_set TIM4_IRQHandler,Default_Handler
+
+ .weak I2C1_EV_IRQHandler
+ .thumb_set I2C1_EV_IRQHandler,Default_Handler
+
+ .weak I2C1_ER_IRQHandler
+ .thumb_set I2C1_ER_IRQHandler,Default_Handler
+
+ .weak I2C2_EV_IRQHandler
+ .thumb_set I2C2_EV_IRQHandler,Default_Handler
+
+ .weak I2C2_ER_IRQHandler
+ .thumb_set I2C2_ER_IRQHandler,Default_Handler
+
+ .weak SPI1_IRQHandler
+ .thumb_set SPI1_IRQHandler,Default_Handler
+
+ .weak SPI2_IRQHandler
+ .thumb_set SPI2_IRQHandler,Default_Handler
+
+ .weak USART1_IRQHandler
+ .thumb_set USART1_IRQHandler,Default_Handler
+
+ .weak USART2_IRQHandler
+ .thumb_set USART2_IRQHandler,Default_Handler
+
+ .weak EXTI15_10_IRQHandler
+ .thumb_set EXTI15_10_IRQHandler,Default_Handler
+
+ .weak RTC_Alarm_IRQHandler
+ .thumb_set RTC_Alarm_IRQHandler,Default_Handler
+
+ .weak OTG_FS_WKUP_IRQHandler
+ .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler
+
+ .weak DMA1_Stream7_IRQHandler
+ .thumb_set DMA1_Stream7_IRQHandler,Default_Handler
+
+ .weak SDIO_IRQHandler
+ .thumb_set SDIO_IRQHandler,Default_Handler
+
+ .weak TIM5_IRQHandler
+ .thumb_set TIM5_IRQHandler,Default_Handler
+
+ .weak SPI3_IRQHandler
+ .thumb_set SPI3_IRQHandler,Default_Handler
+
+ .weak DMA2_Stream0_IRQHandler
+ .thumb_set DMA2_Stream0_IRQHandler,Default_Handler
+
+ .weak DMA2_Stream1_IRQHandler
+ .thumb_set DMA2_Stream1_IRQHandler,Default_Handler
+
+ .weak DMA2_Stream2_IRQHandler
+ .thumb_set DMA2_Stream2_IRQHandler,Default_Handler
+
+ .weak DMA2_Stream3_IRQHandler
+ .thumb_set DMA2_Stream3_IRQHandler,Default_Handler
+
+ .weak DMA2_Stream4_IRQHandler
+ .thumb_set DMA2_Stream4_IRQHandler,Default_Handler
+
+ .weak OTG_FS_IRQHandler
+ .thumb_set OTG_FS_IRQHandler,Default_Handler
+
+ .weak DMA2_Stream5_IRQHandler
+ .thumb_set DMA2_Stream5_IRQHandler,Default_Handler
+
+ .weak DMA2_Stream6_IRQHandler
+ .thumb_set DMA2_Stream6_IRQHandler,Default_Handler
+
+ .weak DMA2_Stream7_IRQHandler
+ .thumb_set DMA2_Stream7_IRQHandler,Default_Handler
+
+ .weak USART6_IRQHandler
+ .thumb_set USART6_IRQHandler,Default_Handler
+
+ .weak I2C3_EV_IRQHandler
+ .thumb_set I2C3_EV_IRQHandler,Default_Handler
+
+ .weak I2C3_ER_IRQHandler
+ .thumb_set I2C3_ER_IRQHandler,Default_Handler
+
+ .weak FPU_IRQHandler
+ .thumb_set FPU_IRQHandler,Default_Handler
+
+ .weak SPI4_IRQHandler
+ .thumb_set SPI4_IRQHandler,Default_Handler
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/ports/stm32f4/common-hal/microcontroller/__init__.c b/ports/stm32f4/common-hal/microcontroller/__init__.c
index ffab5d1e50..b9a3c16e4f 100644
--- a/ports/stm32f4/common-hal/microcontroller/__init__.c
+++ b/ports/stm32f4/common-hal/microcontroller/__init__.c
@@ -169,8 +169,8 @@ STATIC const mp_rom_map_elem_t mcu_pin_globals_table[] = {
{ MP_ROM_QSTR(MP_QSTR_PE15), MP_ROM_PTR(&pin_PE15) },
#endif
{ MP_ROM_QSTR(MP_QSTR_PB10), MP_ROM_PTR(&pin_PB10) },
-#if MCU_PACKAGE != 100
- { MP_ROM_QSTR(MP_QSTR_PB11), MP_ROM_PTR(&pin_PB11) },
+#if (0)
+// { MP_ROM_QSTR(MP_QSTR_PB11), MP_ROM_PTR(&pin_PB11) },
#endif
{ MP_ROM_QSTR(MP_QSTR_PB12), MP_ROM_PTR(&pin_PB12) },
{ MP_ROM_QSTR(MP_QSTR_PB13), MP_ROM_PTR(&pin_PB13) },
diff --git a/ports/stm32f4/peripherals/stm32f4/pins.h b/ports/stm32f4/peripherals/stm32f4/pins.h
index ced83562ec..e6a32b64e1 100644
--- a/ports/stm32f4/peripherals/stm32f4/pins.h
+++ b/ports/stm32f4/peripherals/stm32f4/pins.h
@@ -77,13 +77,17 @@ extern const mp_obj_type_t mcu_pin_type;
#define NO_PIN 0xff
// Choose based on chip
-#ifdef STM32F412Zx
-#include "stm32f412zx/pins.h"
+#ifdef STM32F401xE
+#include "stm32f401xe/pins.h"
#endif
#ifdef STM32F411xE
#include "stm32f411xe/pins.h"
#endif
+#ifdef STM32F412Zx
+#include "stm32f412zx/pins.h"
+#endif
#ifdef STM32F405xx
#include "stm32f405xx/pins.h"
#endif
+
#endif // __MICROPY_INCLUDED_STM32F4_PERIPHERALS_PINS_H__
diff --git a/ports/stm32f4/peripherals/stm32f4/stm32f401xe/clocks.c b/ports/stm32f4/peripherals/stm32f4/stm32f401xe/clocks.c
index 883c252d51..53af29b3b7 100644
--- a/ports/stm32f4/peripherals/stm32f4/stm32f401xe/clocks.c
+++ b/ports/stm32f4/peripherals/stm32f4/stm32f401xe/clocks.c
@@ -44,7 +44,7 @@ void stm32f4_peripherals_clocks_init(void) {
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
- RCC_OscInitStruct.PLL.PLLM = 8;
+ RCC_OscInitStruct.PLL.PLLM = 12;
RCC_OscInitStruct.PLL.PLLN = 336;
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV4;
RCC_OscInitStruct.PLL.PLLQ = 7;
diff --git a/ports/stm32f4/peripherals/stm32f4/stm32f401xe/gpio.c b/ports/stm32f4/peripherals/stm32f4/stm32f401xe/gpio.c
index 45dc8fc6fa..28afee5d8e 100644
--- a/ports/stm32f4/peripherals/stm32f4/stm32f401xe/gpio.c
+++ b/ports/stm32f4/peripherals/stm32f4/stm32f401xe/gpio.c
@@ -29,8 +29,6 @@
#include "common-hal/microcontroller/Pin.h"
void stm32f4_peripherals_gpio_init(void) {
- //Enable all GPIO for now
- GPIO_InitTypeDef GPIO_InitStruct = {0};
/* GPIO Ports Clock Enable */
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
diff --git a/ports/stm32f4/supervisor/port.c b/ports/stm32f4/supervisor/port.c
index df5a70cd12..3962f6fa62 100644
--- a/ports/stm32f4/supervisor/port.c
+++ b/ports/stm32f4/supervisor/port.c
@@ -52,6 +52,17 @@ safe_mode_t port_init(void) {
tick_init();
board_init();
+ //Configure LED pins
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ GPIO_InitStruct.Pin = GPIO_PIN_4 | GPIO_PIN_5;
+ GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ HAL_GPIO_WritePin(GPIOB, GPIO_PIN_4, 0);
+ HAL_GPIO_WritePin(GPIOB, GPIO_PIN_5, 1);
+
return NO_SAFE_MODE;
}