Skip to content

Commit

Permalink
added port of WeAct Studio H723VG_LCD board
Browse files Browse the repository at this point in the history
  • Loading branch information
bshewan committed Aug 3, 2024
1 parent 060018b commit e5fff60
Show file tree
Hide file tree
Showing 25 changed files with 1,114 additions and 53 deletions.
9 changes: 6 additions & 3 deletions ports/stm/Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ CFLAGS += -DSTM32_HAL_H="<stm32$(MCU_SERIES_LOWER)xx_hal.h>"
CFLAGS += -DSTM32_SERIES_LOWER='"stm32$(MCU_SERIES_LOWER)"'

# Floating point settings
ifeq ($(MCU_VARIANT),$(filter $(MCU_VARIANT),STM32F765xx STM32F767xx STM32F769xx STM32H743xx))
ifeq ($(MCU_VARIANT),$(filter $(MCU_VARIANT),STM32F765xx STM32F767xx STM32F769xx STM32H743xx STM32H723xx))
CFLAGS += -mfpu=fpv5-d16 -mfloat-abi=hard
else
CFLAGS += -mfpu=fpv4-sp-d16 -mfloat-abi=hard
Expand Down Expand Up @@ -134,6 +134,8 @@ SRC_STM32 = $(addprefix $(HAL_DIR)/Src/stm32$(MCU_SERIES_LOWER)xx_,\
hal_gpio.c \
hal_i2c.c \
hal_i2c_ex.c \
hal_pcd.c \
hal_pcd_ex.c \
hal_pwr.c \
hal_pwr_ex.c \
hal_qspi.c \
Expand All @@ -156,6 +158,7 @@ SRC_STM32 = $(addprefix $(HAL_DIR)/Src/stm32$(MCU_SERIES_LOWER)xx_,\
ll_rcc.c \
ll_sdmmc.c \
ll_usart.c \
ll_usb.c \
ll_utils.c \
)

Expand All @@ -165,7 +168,7 @@ endif

# Need this to avoid UART linker problems. TODO: rewrite to use registered callbacks.
# Does not exist for F4 and lower
ifeq ($(MCU_VARIANT),$(filter $(MCU_VARIANT),STM32F765xx STM32F767xx STM32F769xx STM32H743xx STM32L4R5xx))
ifeq ($(MCU_VARIANT),$(filter $(MCU_VARIANT),STM32F765xx STM32F767xx STM32F769xx STM32H743xx STM32H723xx STM32L4R5xx))
SRC_STM32 += $(HAL_DIR)/Src/stm32$(MCU_SERIES_LOWER)xx_hal_uart_ex.c
endif

Expand Down Expand Up @@ -238,7 +241,7 @@ SRC_QSTR += $(SRC_C) $(SRC_SUPERVISOR) $(SRC_MOD) $(SRC_COMMON_HAL_EXPANDED) $(S
SRC_QSTR_PREPROCESSOR +=

# Bin section settings specific to the STM32H7
ifeq ($(MCU_VARIANT),$(filter $(MCU_VARIANT),STM32H743xx))
ifeq ($(MCU_VARIANT),$(filter $(MCU_VARIANT),STM32H743xx STM32H723xx))
MCU_SECTIONS = -j .isr_vector -j .text -j .data -j .itcm -j .dtcm_data $^ $@
else
MCU_SECTIONS = $^ $@
Expand Down
38 changes: 38 additions & 0 deletions ports/stm/boards/STM32H723_fs.ld
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
/*
GNU linker script for STM32H723 with filesystem, tcm
*/

/* Entry Point */
ENTRY(Reset_Handler)

_ld_default_stack_size = 24K;

/* Specify the memory areas */
MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 1024K
FLASH_ISR (rx) : ORIGIN = 0x08000000, LENGTH = 128K /* sector 0, 128K */
FLASH_FS (r) : ORIGIN = 0x08020000, LENGTH = 384K /* sector 1-3, 128K */
FLASH_FIRMWARE (rx) : ORIGIN = 0x08080000, LENGTH = 512K /* sectors 4*128 + 8*128 */
DTCM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
RAM (xrw) : ORIGIN = 0x24000000, LENGTH = 320K /* AXI SRAM */
SRAM_D2 (xrw) : ORIGIN = 0x30000000, LENGTH = 32K /* AHB1 SRAM */
SRAM_D3 (xrw) : ORIGIN = 0x38000000, LENGTH = 16K /* AHB2 SRAM */
ITCM (xrw) : ORIGIN = 0x00000000, LENGTH = 64K
}

/* produce a link error if there is not this amount of RAM for these sections */
_minimum_stack_size = 24K; /*TODO: this can probably be bigger, but how big?*/
_minimum_heap_size = 16K;

/* brainless copy paste for stack code. Results in ambiguous hard crash */
/* _ld_default_stack_size = 20K; */

/* 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(DTCM) + LENGTH(DTCM);

/* RAM extents for the garbage collector */
_ram_start = ORIGIN(RAM);
_ram_end = ORIGIN(RAM) + LENGTH(RAM);
37 changes: 37 additions & 0 deletions ports/stm/boards/STM32H723_nofs.ld
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
/*
GNU linker script for STM32H723 with no filesystem, tcm
*/

/* Entry Point */
ENTRY(Reset_Handler)

_ld_default_stack_size = 24K;

/* Specify the memory areas */
MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 1024K
FLASH_ISR (rx) : ORIGIN = 0x08000000, LENGTH = 128K /* sector 0, 128K */
FLASH_FIRMWARE (rx) : ORIGIN = 0x08020000, LENGTH = 896K /* sectors 1-15, 15*128 */
DTCM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
RAM (xrw) : ORIGIN = 0x24000000, LENGTH = 320K /* AXI SRAM */
SRAM_D2 (xrw) : ORIGIN = 0x30000000, LENGTH = 32K /* AHB1 SRAM */
SRAM_D3 (xrw) : ORIGIN = 0x38000000, LENGTH = 16K /* AHB2 SRAM */
ITCM (xrw) : ORIGIN = 0x00000000, LENGTH = 64K
}

/* produce a link error if there is not this amount of RAM for these sections */
_minimum_stack_size = 24K; /*TODO: this can probably be bigger, but how big?*/
_minimum_heap_size = 16K;

/* brainless copy paste for stack code. Results in ambiguous hard crash */
/* _ld_default_stack_size = 20K; */

/* 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(DTCM) + LENGTH(DTCM);

/* RAM extents for the garbage collector */
_ram_start = ORIGIN(RAM);
_ram_end = ORIGIN(RAM) + LENGTH(RAM);
2 changes: 1 addition & 1 deletion ports/stm/boards/common_tcm.ld
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ SECTIONS
_ld_d1_ram_bss_start = ADDR(.bss);
_ld_d1_ram_bss_size = SIZEOF(.bss);
_ld_heap_start = _ld_d1_ram_bss_start + _ld_d1_ram_bss_size;
_ld_heap_end = ORIGIN(RAM) + LENGTH(RAM);
_ld_heap_end = ORIGIN(RAM) + LENGTH(RAM) - 1;

/* this is to define the start of the heap, and make sure we have a minimum size */
.heap :
Expand Down
13 changes: 13 additions & 0 deletions ports/stm/boards/weact-h723vg-lcd/board.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
// This file is part of the CircuitPython project: https://circuitpython.org
//
// SPDX-FileCopyrightText: Copyright (c) 2017 Scott Shawcroft for Adafruit Industries
//
// SPDX-License-Identifier: MIT

#include "supervisor/board.h"
#include "stm32h7xx_hal.h"

// Use the MP_WEAK supervisor/shared/board.c versions of routines not defined here.

void board_init(void) {
}
53 changes: 53 additions & 0 deletions ports/stm/boards/weact-h723vg-lcd/mpconfigboard.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
// This file is part of the CircuitPython project: https://circuitpython.org
//
// SPDX-FileCopyrightText: Copyright (c) 2020 Lucian Copeland for Adafruit Industries
//
// SPDX-License-Identifier: MIT

#pragma once

// Micropython setup

#define MICROPY_HW_BOARD_NAME "WeAct H723VG LCD"
#define MICROPY_HW_MCU_NAME "STM32H723"

#define FLASH_PAGE_SIZE (0x4000)

// H7 and F7 MPU definitions
#define CPY_FLASH_REGION_SIZE ARM_MPU_REGION_SIZE_1MB
#define CPY_ITCM_REGION_SIZE ARM_MPU_REGION_SIZE_64KB
#define CPY_DTCM_REGION_SIZE ARM_MPU_REGION_SIZE_128KB
#define CPY_SRAM_REGION_SIZE ARM_MPU_REGION_SIZE_320KB
#define CPY_SRAM_SUBMASK 0x00
#define CPY_SRAM_START_ADDR 0x24000000
#define CFG_TUSB_OS OPT_OS_NONE

#define HSE_VALUE ((uint32_t)25000000)
#define LSE_VALUE ((uint32_t)32768)

#define BOARD_HSE_SOURCE (RCC_HSE_ON)
#define BOARD_HAS_LOW_SPEED_CRYSTAL (0)
#define BOARD_NO_VBUS_SENSE 1
#define BOARD_NO_USB_OTG_ID_SENSE 1

#define MICROPY_HW_LED_STATUS (&pin_PE03)

// on-board SPI flash
#define SPI_FLASH_MOSI_PIN (&pin_PD07)
#define SPI_FLASH_MISO_PIN (&pin_PB04)
#define SPI_FLASH_SCK_PIN (&pin_PB03)
#define SPI_FLASH_CS_PIN (&pin_PD06)

// usb?
#define IGNORE_PIN_PA11 1
#define IGNORE_PIN_PA12 1

#define DEFAULT_I2C_BUS_SCL (&pin_PB08)
#define DEFAULT_I2C_BUS_SDA (&pin_PB09)

#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_PA10)
#define DEFAULT_UART_BUS_TX (&pin_PA09)
63 changes: 63 additions & 0 deletions ports/stm/boards/weact-h723vg-lcd/mpconfigboard.mk
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
USB_VID = 0x0483
USB_PID = 0x5740
USB_PRODUCT = "H723VG LCD"
USB_MANUFACTURER = "WeAct Studio"

INTERNAL_FLASH_FILESYSTEM = 0
# QSPI_FLASH_FILESYSTEM = 1
SPI_FLASH_FILESYSTEM = 1

MCU_SERIES = H7
MCU_VARIANT = STM32H723xx
MCU_PACKAGE = LQFP100_x7

EXTERNAL_FLASH_DEVICES = "W25Q64JVxQ"

LD_COMMON = boards/common_tcm.ld
LD_FILE = boards/STM32H723_nofs.ld

CIRCUITPY_BLEIO_HCI = 0

# Typically the first module to create
CIRCUITPY_MICROCONTROLLER = 1
# Typically the second module to create
CIRCUITPY_DIGITALIO = 1
# Other modules:
CIRCUITPY_ANALOGIO = 0
CIRCUITPY_PWMIO = 1
CIRCUITPY_BUSIO = 1
CIRCUITPY_COUNTIO = 0
CIRCUITPY_NEOPIXEL_WRITE = 0
CIRCUITPY_PULSEIO = 1
CIRCUITPY_OS = 1
CIRCUITPY_NVM = 0
CIRCUITPY_AUDIOBUSIO = 0
CIRCUITPY_AUDIOIO = 0
CIRCUITPY_ROTARYIO = 0
CIRCUITPY_RTC = 1
CIRCUITPY_SDCARDIO = 1
CIRCUITPY_FRAMEBUFFERIO = 0
CIRCUITPY_FREQUENCYIO = 0
CIRCUITPY_I2CTARGET = 0
# Requires SPI, PulseIO (stub ok):
CIRCUITPY_DISPLAYIO = 1

# These modules are implemented in shared-module/ - they can be included in
# any port once their prerequisites in common-hal are complete.
# Requires DigitalIO:
CIRCUITPY_BITBANGIO = 0
# Requires neopixel_write or SPI (dotstar)
CIRCUITPY_PIXELBUF = 0
# Requires OS
CIRCUITPY_RANDOM = 1
# Requires OS, filesystem
CIRCUITPY_STORAGE = 1
# Requires Microcontroller
CIRCUITPY_TOUCHIO = 0
# Requires USB
CIRCUITPY_USB_HID = 0
CIRCUITPY_USB_MIDI = 0
# Does nothing without I2C
CIRCUITPY_REQUIRE_I2C_PULLUPS = 0
# No requirements, but takes extra flash
CIRCUITPY_ULAB = 0
98 changes: 98 additions & 0 deletions ports/stm/boards/weact-h723vg-lcd/pins.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,98 @@
// This file is part of the CircuitPython project: https://circuitpython.org
//
// SPDX-FileCopyrightText: Copyright (c) 2017 Scott Shawcroft for Adafruit Industries
//
// SPDX-License-Identifier: MIT

#include "shared-bindings/board/__init__.h"

static const mp_rom_map_elem_t board_module_globals_table[] = {
CIRCUITPYTHON_BOARD_DICT_STANDARD_ITEMS

{ MP_ROM_QSTR(MP_QSTR_A0), MP_ROM_PTR(&pin_PA00) },
{ MP_ROM_QSTR(MP_QSTR_A1), MP_ROM_PTR(&pin_PA01) },
{ MP_ROM_QSTR(MP_QSTR_A2), MP_ROM_PTR(&pin_PA02) },
{ MP_ROM_QSTR(MP_QSTR_A3), MP_ROM_PTR(&pin_PA03) },
{ MP_ROM_QSTR(MP_QSTR_A4), MP_ROM_PTR(&pin_PA04) },
{ MP_ROM_QSTR(MP_QSTR_A5), MP_ROM_PTR(&pin_PA05) },
{ MP_ROM_QSTR(MP_QSTR_A6), MP_ROM_PTR(&pin_PA06) },
{ MP_ROM_QSTR(MP_QSTR_A7), MP_ROM_PTR(&pin_PA07) },
{ MP_ROM_QSTR(MP_QSTR_A8), MP_ROM_PTR(&pin_PA08) },
{ MP_ROM_QSTR(MP_QSTR_A9), MP_ROM_PTR(&pin_PA09) },
{ MP_ROM_QSTR(MP_QSTR_A10), MP_ROM_PTR(&pin_PA10) },
{ MP_ROM_QSTR(MP_QSTR_A11), MP_ROM_PTR(&pin_PA11) },
{ MP_ROM_QSTR(MP_QSTR_A12), MP_ROM_PTR(&pin_PA12) },
{ MP_ROM_QSTR(MP_QSTR_A15), MP_ROM_PTR(&pin_PA15) },

{ MP_ROM_QSTR(MP_QSTR_B0), MP_ROM_PTR(&pin_PB00) },
{ MP_ROM_QSTR(MP_QSTR_B1), MP_ROM_PTR(&pin_PB01) },
{ MP_ROM_QSTR(MP_QSTR_B2), MP_ROM_PTR(&pin_PB02) },
{ MP_ROM_QSTR(MP_QSTR_B3), MP_ROM_PTR(&pin_PB03) },
{ MP_ROM_QSTR(MP_QSTR_B4), MP_ROM_PTR(&pin_PB04) },
{ MP_ROM_QSTR(MP_QSTR_B5), MP_ROM_PTR(&pin_PB05) },
{ MP_ROM_QSTR(MP_QSTR_B6), MP_ROM_PTR(&pin_PB06) },
{ MP_ROM_QSTR(MP_QSTR_B7), MP_ROM_PTR(&pin_PB07) },
{ MP_ROM_QSTR(MP_QSTR_B8), MP_ROM_PTR(&pin_PB08) },
{ MP_ROM_QSTR(MP_QSTR_B9), MP_ROM_PTR(&pin_PB09) },
{ MP_ROM_QSTR(MP_QSTR_B10), MP_ROM_PTR(&pin_PB10) },
{ MP_ROM_QSTR(MP_QSTR_B11), MP_ROM_PTR(&pin_PB11) },
{ MP_ROM_QSTR(MP_QSTR_B12), MP_ROM_PTR(&pin_PB12) },
{ MP_ROM_QSTR(MP_QSTR_B13), MP_ROM_PTR(&pin_PB13) },
{ MP_ROM_QSTR(MP_QSTR_B14), MP_ROM_PTR(&pin_PB14) },
{ MP_ROM_QSTR(MP_QSTR_B15), MP_ROM_PTR(&pin_PB15) },

{ MP_ROM_QSTR(MP_QSTR_C0), MP_ROM_PTR(&pin_PC00) },
{ MP_ROM_QSTR(MP_QSTR_C1), MP_ROM_PTR(&pin_PC01) },
{ MP_ROM_QSTR(MP_QSTR_C2), MP_ROM_PTR(&pin_PC02) },
{ MP_ROM_QSTR(MP_QSTR_C3), MP_ROM_PTR(&pin_PC03) },
{ MP_ROM_QSTR(MP_QSTR_C4), MP_ROM_PTR(&pin_PC04) },
{ MP_ROM_QSTR(MP_QSTR_C5), MP_ROM_PTR(&pin_PC05) },
{ MP_ROM_QSTR(MP_QSTR_C6), MP_ROM_PTR(&pin_PC06) },
{ MP_ROM_QSTR(MP_QSTR_C7), MP_ROM_PTR(&pin_PC07) },
{ MP_ROM_QSTR(MP_QSTR_C8), MP_ROM_PTR(&pin_PC08) },
{ MP_ROM_QSTR(MP_QSTR_C9), MP_ROM_PTR(&pin_PC09) },
{ MP_ROM_QSTR(MP_QSTR_C10), MP_ROM_PTR(&pin_PC10) },
{ MP_ROM_QSTR(MP_QSTR_C11), MP_ROM_PTR(&pin_PC11) },
{ MP_ROM_QSTR(MP_QSTR_C12), MP_ROM_PTR(&pin_PC12) },
{ MP_ROM_QSTR(MP_QSTR_C13), MP_ROM_PTR(&pin_PC13) },

{ MP_ROM_QSTR(MP_QSTR_D0), MP_ROM_PTR(&pin_PD00) },
{ MP_ROM_QSTR(MP_QSTR_D1), MP_ROM_PTR(&pin_PD01) },
{ MP_ROM_QSTR(MP_QSTR_D2), MP_ROM_PTR(&pin_PD02) },
{ MP_ROM_QSTR(MP_QSTR_D3), MP_ROM_PTR(&pin_PD03) },
{ MP_ROM_QSTR(MP_QSTR_D4), MP_ROM_PTR(&pin_PD04) },
{ MP_ROM_QSTR(MP_QSTR_D5), MP_ROM_PTR(&pin_PD05) },
{ MP_ROM_QSTR(MP_QSTR_D6), MP_ROM_PTR(&pin_PD06) },
{ MP_ROM_QSTR(MP_QSTR_D7), MP_ROM_PTR(&pin_PD07) },
{ MP_ROM_QSTR(MP_QSTR_D8), MP_ROM_PTR(&pin_PD08) },
{ MP_ROM_QSTR(MP_QSTR_D9), MP_ROM_PTR(&pin_PD09) },
{ MP_ROM_QSTR(MP_QSTR_D10), MP_ROM_PTR(&pin_PD10) },
{ MP_ROM_QSTR(MP_QSTR_D11), MP_ROM_PTR(&pin_PD11) },
{ MP_ROM_QSTR(MP_QSTR_D12), MP_ROM_PTR(&pin_PD12) },
{ MP_ROM_QSTR(MP_QSTR_D13), MP_ROM_PTR(&pin_PD13) },
{ MP_ROM_QSTR(MP_QSTR_D14), MP_ROM_PTR(&pin_PD14) },
{ MP_ROM_QSTR(MP_QSTR_D15), MP_ROM_PTR(&pin_PD15) },

{ MP_ROM_QSTR(MP_QSTR_E0), MP_ROM_PTR(&pin_PE00) },
{ MP_ROM_QSTR(MP_QSTR_E1), MP_ROM_PTR(&pin_PE01) },
{ MP_ROM_QSTR(MP_QSTR_E2), MP_ROM_PTR(&pin_PE02) },
{ MP_ROM_QSTR(MP_QSTR_E3), MP_ROM_PTR(&pin_PE03) },
{ MP_ROM_QSTR(MP_QSTR_E4), MP_ROM_PTR(&pin_PE04) },
{ MP_ROM_QSTR(MP_QSTR_E5), MP_ROM_PTR(&pin_PE05) },
{ MP_ROM_QSTR(MP_QSTR_E6), MP_ROM_PTR(&pin_PE06) },
{ MP_ROM_QSTR(MP_QSTR_E7), MP_ROM_PTR(&pin_PE07) },
{ MP_ROM_QSTR(MP_QSTR_E8), MP_ROM_PTR(&pin_PE08) },
{ MP_ROM_QSTR(MP_QSTR_E9), MP_ROM_PTR(&pin_PE09) },
{ MP_ROM_QSTR(MP_QSTR_E10), MP_ROM_PTR(&pin_PE10) },
{ MP_ROM_QSTR(MP_QSTR_E11), MP_ROM_PTR(&pin_PE11) },
{ MP_ROM_QSTR(MP_QSTR_E12), MP_ROM_PTR(&pin_PE12) },
{ MP_ROM_QSTR(MP_QSTR_E13), MP_ROM_PTR(&pin_PE13) },
{ MP_ROM_QSTR(MP_QSTR_E14), MP_ROM_PTR(&pin_PE14) },
{ MP_ROM_QSTR(MP_QSTR_E15), MP_ROM_PTR(&pin_PE15) },

{ MP_ROM_QSTR(MP_QSTR_LED), MP_ROM_PTR(&pin_PE03) },
{ MP_ROM_QSTR(MP_QSTR_SW), MP_ROM_PTR(&pin_PC13) },

{ MP_ROM_QSTR(MP_QSTR_SPI), MP_ROM_PTR(&board_spi_obj) },
};
MP_DEFINE_CONST_DICT(board_module_globals, board_module_globals_table);
2 changes: 1 addition & 1 deletion ports/stm/common-hal/pulseio/PulseIn.c
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ static void pulsein_exti_event_handler(uint8_t num) {
uint32_t current_count = tim_handle.Instance->CNT;

// Interrupt register must be cleared manually
#if CPY_STM32L4
#if CPY_STM32L4 || CPY_STM32H7
EXTI->PR1 = 1 << num;
#else
EXTI->PR = 1 << num;
Expand Down
2 changes: 1 addition & 1 deletion ports/stm/hal_conf/stm32h7xx_hal_conf.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ extern "C" {
* (when HSE is used as system clock source, directly or through the PLL).
*/
#if !defined(HSE_VALUE)
#define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz : FPGA case fixed to 60MHZ */
#define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz : FPGA case fixed to 60MHZ */
#endif /* HSE_VALUE */

#if !defined(HSE_STARTUP_TIMEOUT)
Expand Down
Loading

0 comments on commit e5fff60

Please sign in to comment.