add ci build for all at32, use linker and startup from mcu cmsis instead of local files

This commit is contained in:
hathach
2025-07-31 21:52:59 +07:00
parent b531f43434
commit b67e00892c
50 changed files with 1023 additions and 4837 deletions

View File

@@ -1,154 +0,0 @@
/*
*****************************************************************************
**
** File : AT32F437xM_FLASH.ld
**
** Abstract : Linker script for AT32F437xM Device with
** 4096KByte FLASH, 384KByte RAM
**
** Set heap size, stack size and stack location according
** to application requirements.
**
** Set memory bank area and size if external memory is used.
**
** Target : Artery Tek AT32
**
** Environment : Arm gcc toolchain
**
*****************************************************************************
*/
/* Entry Point */
ENTRY(Reset_Handler)
/* Highest address of the user mode stack */
_estack = 0x20060000; /* end of RAM */
/* Generate a link error if heap and stack don't fit into RAM */
_Min_Heap_Size = 0x200; /* required amount of heap */
_Min_Stack_Size = 0x400; /* required amount of stack */
/* Specify the memory areas */
MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 4032K
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 384K
}
/* Define output sections */
SECTIONS
{
/* The startup code goes first into FLASH */
.isr_vector :
{
. = ALIGN(4);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} >FLASH
/* The program code and other data goes into FLASH */
.text :
{
. = ALIGN(4);
*(.text) /* .text sections (code) */
*(.text*) /* .text* sections (code) */
*(.glue_7) /* glue arm to thumb code */
*(.glue_7t) /* glue thumb to arm code */
*(.eh_frame)
KEEP (*(.init))
KEEP (*(.fini))
. = ALIGN(4);
_etext = .; /* define a global symbols at end of code */
} >FLASH
/* Constant data goes into FLASH */
.rodata :
{
. = ALIGN(4);
*(.rodata) /* .rodata sections (constants, strings, etc.) */
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
. = ALIGN(4);
} >FLASH
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
.ARM : {
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
} >FLASH
.preinit_array :
{
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP (*(.preinit_array*))
PROVIDE_HIDDEN (__preinit_array_end = .);
} >FLASH
.init_array :
{
PROVIDE_HIDDEN (__init_array_start = .);
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array*))
PROVIDE_HIDDEN (__init_array_end = .);
} >FLASH
.fini_array :
{
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP (*(SORT(.fini_array.*)))
KEEP (*(.fini_array*))
PROVIDE_HIDDEN (__fini_array_end = .);
} >FLASH
/* used by the startup to initialize data */
_sidata = LOADADDR(.data);
/* Initialized data sections goes into RAM, load LMA copy after code */
.data :
{
. = ALIGN(4);
_sdata = .; /* create a global symbol at data start */
*(.data) /* .data sections */
*(.data*) /* .data* sections */
. = ALIGN(4);
_edata = .; /* define a global symbol at data end */
} >RAM AT> FLASH
/* Uninitialized data section */
. = ALIGN(4);
.bss :
{
/* This is used by the startup in order to initialize the .bss section */
_sbss = .; /* define a global symbol at bss start */
__bss_start__ = _sbss;
*(.bss)
*(.bss*)
*(COMMON)
. = ALIGN(4);
_ebss = .; /* define a global symbol at bss end */
__bss_end__ = _ebss;
} >RAM
/* User_heap_stack section, used to check that there is enough RAM left */
._user_heap_stack :
{
. = ALIGN(8);
PROVIDE ( end = . );
PROVIDE ( _end = . );
. = . + _Min_Heap_Size;
. = . + _Min_Stack_Size;
. = ALIGN(8);
} >RAM
/* Remove information from the standard libraries */
/DISCARD/ :
{
libc.a ( * )
libm.a ( * )
libgcc.a ( * )
}
.ARM.attributes 0 : { *(.ARM.attributes) }
}

View File

@@ -0,0 +1,8 @@
set(MCU_VARIANT AT32F437ZMT7)
set(MCU_LINKER_NAME AT32F437xM)
set(JLINK_DEVICE ${MCU_VARIANT})
function(update_board TARGET)
target_compile_definitions(${TARGET} PUBLIC ${MCU_VARIANT})
endfunction()

View File

@@ -1,4 +1,7 @@
LD_FILE = $(BOARD_PATH)/AT32F437xM_FLASH.ld
MCU_VARIANT = AT32F437ZMT7
MCU_LINKER_NAME = AT32F437xM
JLINK_DEVICE = ${MCU_VARIANT}
CFLAGS += \
-DAT32F437ZMT7
-D${MCU_VARIANT}

View File

@@ -25,8 +25,8 @@
*/
#include "at32f435_437_clock.h"
#include "bsp/board_api.h"
#include "board.h"
#include "bsp/board_api.h"
void usb_gpio_config(void);
void uart_print_init(uint32_t baudrate);
@@ -36,25 +36,20 @@ int inHandlerMode(void);
//--------------------------------------------------------------------+
// Forward USB interrupt events to TinyUSB IRQ Handler
//--------------------------------------------------------------------+
void OTGFS1_IRQHandler(void)
{
void OTGFS1_IRQHandler(void) {
tusb_int_handler(0, true);
}
void OTGFS2_IRQHandler(void)
{
void OTGFS2_IRQHandler(void) {
tusb_int_handler(1, true);
}
void OTGFS1_WKUP_IRQHandler(void)
{
void OTGFS1_WKUP_IRQHandler(void) {
tusb_int_handler(0, true);
}
void OTGFS2_WKUP_IRQHandler(void)
{
void OTGFS2_WKUP_IRQHandler(void) {
tusb_int_handler(1, true);
}
void board_init(void)
{
void board_init(void) {
/* config nvic priority group */
nvic_priority_group_config(NVIC_PRIORITY_GROUP_4);
@@ -97,10 +92,8 @@ void board_init(void)
* @param clk_s:USB_CLK_HICK, USB_CLK_HEXT
* @retval none
*/
void usb_clock48m_select(usb_clk48_s clk_s)
{
if(clk_s == USB_CLK_HICK)
{
void usb_clock48m_select(usb_clk48_s clk_s) {
if (clk_s == USB_CLK_HICK) {
crm_usb_clock_source_select(CRM_USB_CLOCK_SOURCE_HICK);
/* enable the acc calibration ready interrupt */
@@ -110,20 +103,17 @@ void usb_clock48m_select(usb_clk48_s clk_s)
acc_write_c1(7980);
acc_write_c2(8000);
acc_write_c3(8020);
#ifdef BOARD_TUD_RHPORT
#if BOARD_TUD_RHPORT == 0
acc_sof_select(ACC_SOF_OTG1);
#else
acc_sof_select(ACC_SOF_OTG2);
#endif
#endif
#ifdef BOARD_TUD_RHPORT
#if BOARD_TUD_RHPORT == 0
acc_sof_select(ACC_SOF_OTG1);
#else
acc_sof_select(ACC_SOF_OTG2);
#endif
#endif
/* open acc calibration */
acc_calibration_mode_enable(ACC_CAL_HICKTRIM, TRUE);
}
else
{
switch(system_core_clock)
{
} else {
switch (system_core_clock) {
/* 48MHz */
case 48000000:
crm_usb_clock_div_set(CRM_USB_DIV_1);
@@ -185,8 +175,7 @@ void usb_clock48m_select(usb_clk48_s clk_s)
}
}
void led_and_botton_init(void)
{
void led_and_botton_init(void) {
/* LED */
gpio_init_type gpio_led_init_struct;
/* enable the led clock */
@@ -195,7 +184,7 @@ void led_and_botton_init(void)
gpio_default_para_init(&gpio_led_init_struct);
/* configure the led gpio */
gpio_led_init_struct.gpio_drive_strength = GPIO_DRIVE_STRENGTH_STRONGER;
gpio_led_init_struct.gpio_out_type = GPIO_OUTPUT_PUSH_PULL;
gpio_led_init_struct.gpio_out_type = GPIO_OUTPUT_PUSH_PULL;
gpio_led_init_struct.gpio_mode = GPIO_MODE_OUTPUT;
gpio_led_init_struct.gpio_pins = LED_PIN;
gpio_led_init_struct.gpio_pull = GPIO_PULL_NONE;
@@ -223,8 +212,7 @@ void led_and_botton_init(void)
* @param baudrate: uart baudrate
* @retval none
*/
void uart_print_init(uint32_t baudrate)
{
void uart_print_init(uint32_t baudrate) {
gpio_init_type gpio_init_struct;
/* enable the uart and gpio clock */
crm_periph_clock_enable(PRINT_UART_CRM_CLK, TRUE);
@@ -232,7 +220,7 @@ void uart_print_init(uint32_t baudrate)
gpio_default_para_init(&gpio_init_struct);
/* configure the uart tx pin */
gpio_init_struct.gpio_drive_strength = GPIO_DRIVE_STRENGTH_STRONGER;
gpio_init_struct.gpio_out_type = GPIO_OUTPUT_PUSH_PULL;
gpio_init_struct.gpio_out_type = GPIO_OUTPUT_PUSH_PULL;
gpio_init_struct.gpio_mode = GPIO_MODE_MUX;
gpio_init_struct.gpio_pins = PRINT_UART_TX_PIN;
gpio_init_struct.gpio_pull = GPIO_PULL_NONE;
@@ -245,51 +233,44 @@ void uart_print_init(uint32_t baudrate)
}
// Get characters from UART. Return number of read bytes
int board_uart_read(uint8_t *buf, int len)
{
int board_uart_read(uint8_t *buf, int len) {
(void) buf;
(void) len;
return 0;
}
// Send characters to UART. Return number of sent bytes
int board_uart_write(void const *buf, int len)
{
#if CFG_TUSB_OS == OPT_OS_NONE
int txsize = len;
u16 timeout = 0xffff;
while (txsize--)
{
while(usart_flag_get(PRINT_UART, USART_TDBE_FLAG) == RESET)
{
timeout--;
if(timeout == 0)
{
return 0;
}
int board_uart_write(void const *buf, int len) {
#if CFG_TUSB_OS == OPT_OS_NONE
int txsize = len;
u16 timeout = 0xffff;
while (txsize--) {
while (usart_flag_get(PRINT_UART, USART_TDBE_FLAG) == RESET) {
timeout--;
if (timeout == 0) {
return 0;
}
PRINT_UART->dt = (*((uint8_t const *)buf) & 0x01FF);
buf++;
}
return len;
#else
(void) buf;
(void) len;
return 0;
#endif
PRINT_UART->dt = (*((uint8_t const *) buf) & 0x01FF);
buf++;
}
return len;
#else
(void) buf;
(void) len;
return 0;
#endif
}
int inHandlerMode(void)
{
return __get_IPSR();
int inHandlerMode(void) {
return __get_IPSR();
}
void usb_gpio_config(void)
{
void usb_gpio_config(void) {
gpio_init_type gpio_init_struct;
crm_periph_clock_enable(OTG_PIN_GPIO_CLOCK, TRUE);
gpio_default_para_init(&gpio_init_struct);
gpio_init_struct.gpio_drive_strength = GPIO_DRIVE_STRENGTH_STRONGER;
gpio_init_struct.gpio_out_type = GPIO_OUTPUT_PUSH_PULL;
gpio_init_struct.gpio_out_type = GPIO_OUTPUT_PUSH_PULL;
gpio_init_struct.gpio_mode = GPIO_MODE_MUX;
gpio_init_struct.gpio_pull = GPIO_PULL_NONE;
/* dp and dm */
@@ -297,36 +278,33 @@ void usb_gpio_config(void)
gpio_init(OTG_PIN_GPIO, &gpio_init_struct);
gpio_pin_mux_config(OTG_PIN_GPIO, OTG_PIN_DP_SOURCE, OTG_PIN_MUX);
gpio_pin_mux_config(OTG_PIN_GPIO, OTG_PIN_DM_SOURCE, OTG_PIN_MUX);
#ifdef USB_SOF_OUTPUT_ENABLE
crm_periph_clock_enable(OTG_PIN_SOF_GPIO_CLOCK, TRUE);
gpio_init_struct.gpio_pins = OTG_PIN_SOF;
gpio_init(OTG_PIN_SOF_GPIO, &gpio_init_struct);
gpio_pin_mux_config(OTG_PIN_SOF_GPIO, OTG_PIN_SOF_SOURCE, OTG_PIN_MUX);
#endif
/* otgfs use vbus pin */
#ifndef USB_VBUS_IGNORE
gpio_init_struct.gpio_pins = OTG_PIN_VBUS;
gpio_init_struct.gpio_pull = GPIO_PULL_DOWN;
gpio_pin_mux_config(OTG_PIN_GPIO, OTG_PIN_VBUS_SOURCE, OTG_PIN_MUX);
gpio_init(OTG_PIN_GPIO, &gpio_init_struct);
#endif
#ifdef USB_SOF_OUTPUT_ENABLE
crm_periph_clock_enable(OTG_PIN_SOF_GPIO_CLOCK, TRUE);
gpio_init_struct.gpio_pins = OTG_PIN_SOF;
gpio_init(OTG_PIN_SOF_GPIO, &gpio_init_struct);
gpio_pin_mux_config(OTG_PIN_SOF_GPIO, OTG_PIN_SOF_SOURCE, OTG_PIN_MUX);
#endif
/* otgfs use vbus pin */
#ifndef USB_VBUS_IGNORE
gpio_init_struct.gpio_pins = OTG_PIN_VBUS;
gpio_init_struct.gpio_pull = GPIO_PULL_DOWN;
gpio_pin_mux_config(OTG_PIN_GPIO, OTG_PIN_VBUS_SOURCE, OTG_PIN_MUX);
gpio_init(OTG_PIN_GPIO, &gpio_init_struct);
#endif
}
void board_led_write(bool state)
{
void board_led_write(bool state) {
gpio_bits_write(LED_PORT, LED_PIN, state ^ (!LED_STATE_ON));
}
uint32_t board_button_read(void)
{
uint32_t board_button_read(void) {
return gpio_input_data_bit_read(BUTTON_PORT, BUTTON_PIN);
}
size_t board_get_unique_id(uint8_t id[], size_t max_len)
{
size_t board_get_unique_id(uint8_t id[], size_t max_len) {
(void) max_len;
volatile uint32_t * at32_uuid = ((volatile uint32_t*)0x1FFFF7E8);
uint32_t* id32 = (uint32_t*) (uintptr_t) id;
volatile uint32_t *at32_uuid = ((volatile uint32_t *) 0x1FFFF7E8);
uint32_t *id32 = (uint32_t *) (uintptr_t) id;
uint8_t const len = 12;
id32[0] = at32_uuid[0];
@@ -337,21 +315,17 @@ size_t board_get_unique_id(uint8_t id[], size_t max_len)
}
#if CFG_TUSB_OS == OPT_OS_NONE
volatile uint32_t system_ticks = 0;
void SysTick_Handler(void)
{
system_ticks++;
}
uint32_t board_millis(void)
{
return system_ticks;
}
void SVC_Handler(void)
{
}
void PendSV_Handler(void)
{
}
volatile uint32_t system_ticks = 0;
void SysTick_Handler(void) {
system_ticks++;
}
uint32_t board_millis(void) {
return system_ticks;
}
void SVC_Handler(void) {
}
void PendSV_Handler(void) {
}
#endif
void HardFault_Handler(void) {
@@ -363,9 +337,8 @@ void HardFault_Handler(void) {
void _init(void) {
}
#ifdef USE_FULL_ASSERT
void assert_failed(const char *file, uint32_t line)
{
#ifdef USE_FULL_ASSERT
void assert_failed(const char *file, uint32_t line) {
/* USER CODE BEGIN 6 */
/* User can add his own implementation to report the file name and line number,
tex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */

View File

@@ -0,0 +1,114 @@
include_guard()
set(AT32_FAMILY at32f435_437)
set(AT32_SDK_LIB ${TOP}/hw/mcu/artery/${AT32_FAMILY}/libraries)
string(TOUPPER ${AT32_FAMILY} AT32_FAMILY_UPPER)
# include board specific
include(${CMAKE_CURRENT_LIST_DIR}/boards/${BOARD}/board.cmake)
# toolchain set up
set(CMAKE_SYSTEM_CPU cortex-m4 CACHE INTERNAL "System Processor")
set(CMAKE_TOOLCHAIN_FILE ${TOP}/examples/build_system/cmake/toolchain/arm_${TOOLCHAIN}.cmake)
set(FAMILY_MCUS ${AT32_FAMILY_UPPER} CACHE INTERNAL "")
#------------------------------------
# BOARD_TARGET
#------------------------------------
# only need to be built ONCE for all examples
function(add_board_target BOARD_TARGET)
if (TARGET ${BOARD_TARGET})
return()
endif ()
# Startup & Linker script
set(STARTUP_FILE_GNU ${AT32_SDK_LIB}/cmsis/cm4/device_support/startup/gcc/startup_${AT32_FAMILY}.s)
set(STARTUP_FILE_Clang ${STARTUP_FILE_GNU})
set(STARTUP_FILE_IAR ${AT32_SDK_LIB}/cmsis/cm4/device_support/startup/iar/startup_${AT32_FAMILY}.s)
if (NOT DEFINED LD_FILE_GNU)
set(LD_FILE_GNU ${AT32_SDK_LIB}/cmsis/cm4/device_support/startup/gcc/linker/${MCU_LINKER_NAME}_FLASH.ld)
endif ()
set(LD_FILE_Clang ${LD_FILE_GNU})
set(LD_FILE_IAR ${AT32_SDK_LIB}/cmsis/cm4/device_support/startup/iar/linker/${MCU_LINKER_NAME}.icf)
add_library(${BOARD_TARGET} STATIC
${AT32_SDK_LIB}/cmsis/cm4/device_support/system_${AT32_FAMILY}.c
${AT32_SDK_LIB}/drivers/src/${AT32_FAMILY}_gpio.c
${AT32_SDK_LIB}/drivers/src/${AT32_FAMILY}_misc.c
${AT32_SDK_LIB}/drivers/src/${AT32_FAMILY}_usart.c
${AT32_SDK_LIB}/drivers/src/${AT32_FAMILY}_acc.c
${AT32_SDK_LIB}/drivers/src/${AT32_FAMILY}_crm.c
${AT32_SDK_LIB}/drivers/src/${AT32_FAMILY}_exint.c
${STARTUP_FILE_${CMAKE_C_COMPILER_ID}}
)
target_include_directories(${BOARD_TARGET} PUBLIC
${CMAKE_CURRENT_FUNCTION_LIST_DIR}
${AT32_SDK_LIB}/cmsis/cm4/core_support
${AT32_SDK_LIB}/cmsis/cm4/device_support
${AT32_SDK_LIB}/drivers/inc
)
target_compile_definitions(${BOARD_TARGET} PUBLIC
BOARD_TUD_RHPORT=0
)
update_board(${BOARD_TARGET})
if (CMAKE_C_COMPILER_ID STREQUAL "GNU")
target_link_options(${BOARD_TARGET} PUBLIC
"LINKER:--script=${LD_FILE_GNU}"
-nostartfiles
--specs=nosys.specs --specs=nano.specs
)
elseif (CMAKE_C_COMPILER_ID STREQUAL "Clang")
target_link_options(${BOARD_TARGET} PUBLIC
"LINKER:--script=${LD_FILE_Clang}"
)
elseif (CMAKE_C_COMPILER_ID STREQUAL "IAR")
target_link_options(${BOARD_TARGET} PUBLIC
"LINKER:--config=${LD_FILE_IAR}"
)
endif ()
endfunction()
#------------------------------------
# Functions
#------------------------------------
function(family_configure_example TARGET RTOS)
family_configure_common(${TARGET} ${RTOS})
# Board target
add_board_target(board_${BOARD})
#---------- Port Specific ----------
# These files are built for each example since it depends on example's tusb_config.h
target_sources(${TARGET} PUBLIC
# BSP
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/family.c
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../board.c
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/${AT32_FAMILY}_clock.c
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/${AT32_FAMILY}_int.c
)
target_include_directories(${TARGET} PUBLIC
# family, hw, board
${CMAKE_CURRENT_FUNCTION_LIST_DIR}
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../../
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/boards/${BOARD}
)
# Add TinyUSB target and port source
family_add_tinyusb(${TARGET} OPT_MCU_${AT32_FAMILY_UPPER})
target_sources(${TARGET} PUBLIC
${TOP}/src/portable/synopsys/dwc2/dcd_dwc2.c
${TOP}/src/portable/synopsys/dwc2/hcd_dwc2.c
${TOP}/src/portable/synopsys/dwc2/dwc2_common.c
)
target_link_libraries(${TARGET} PUBLIC board_${BOARD})
# Flashing
family_add_bin_hex(${TARGET})
family_flash_jlink(${TARGET})
endfunction()

View File

@@ -1,8 +1,5 @@
# Submodules
AT32F435_437_SDK = hw/mcu/artery/at32f435_437
# AT32 SDK path
AT32F435_437_SDK_SRC = $(AT32F435_437_SDK)/libraries
AT32_FAMILY = at32f435_437
AT32_SDK_LIB = hw/mcu/artery/${AT32_FAMILY}/libraries
include $(TOP)/$(BOARD_PATH)/board.mk
@@ -13,6 +10,7 @@ CFLAGS_GCC += \
CFLAGS += \
-DCFG_TUSB_MCU=OPT_MCU_AT32F435_437 \
-DBOARD_TUD_RHPORT=0
LDFLAGS_GCC += \
-flto --specs=nosys.specs -nostdlib -nostartfiles
@@ -21,24 +19,24 @@ SRC_C += \
src/portable/synopsys/dwc2/dcd_dwc2.c \
src/portable/synopsys/dwc2/hcd_dwc2.c \
src/portable/synopsys/dwc2/dwc2_common.c \
$(AT32F435_437_SDK_SRC)/drivers/src/at32f435_437_gpio.c \
$(AT32F435_437_SDK_SRC)/drivers/src/at32f435_437_misc.c \
$(AT32F435_437_SDK_SRC)/drivers/src/at32f435_437_usart.c \
$(AT32F435_437_SDK_SRC)/drivers/src/at32f435_437_crm.c \
$(AT32F435_437_SDK_SRC)/drivers/src/at32f435_437_acc.c \
$(AT32F435_437_SDK_SRC)/drivers/src/at32f435_437_exint.c \
$(AT32F435_437_SDK_SRC)/cmsis/cm4/device_support/system_at32f435_437.c
$(AT32_SDK_LIB)/drivers/src/${AT32_FAMILY}_gpio.c \
$(AT32_SDK_LIB)/drivers/src/${AT32_FAMILY}_misc.c \
$(AT32_SDK_LIB)/drivers/src/${AT32_FAMILY}_usart.c \
$(AT32_SDK_LIB)/drivers/src/${AT32_FAMILY}_crm.c \
$(AT32_SDK_LIB)/drivers/src/${AT32_FAMILY}_acc.c \
$(AT32_SDK_LIB)/drivers/src/${AT32_FAMILY}_exint.c \
$(AT32_SDK_LIB)/cmsis/cm4/device_support/system_${AT32_FAMILY}.c
INC += \
$(TOP)/$(BOARD_PATH) \
$(TOP)/$(AT32F435_437_SDK_SRC)/drivers/inc \
$(TOP)/$(AT32F435_437_SDK_SRC)/cmsis/cm4/core_support \
$(TOP)/$(AT32F435_437_SDK_SRC)/cmsis/cm4/device_support \
$(TOP)/$(AT32_SDK_LIB)/drivers/inc \
$(TOP)/$(AT32_SDK_LIB)/cmsis/cm4/core_support \
$(TOP)/$(AT32_SDK_LIB)/cmsis/cm4/device_support
SRC_S += \
$(FAMILY_PATH)/startup_at32f435_437.s
SRC_S_GCC += ${AT32_SDK_LIB}/cmsis/cm4/device_support/startup/gcc/startup_${AT32_FAMILY}.s
SRC_S_IAR += ${AT32_SDK_LIB}/cmsis/cm4/device_support/startup/iar/startup_${AT32_FAMILY}.s
# For freeRTOS port source
#FREERTOS_PORTABLE_SRC = $(FREERTOS_PORTABLE_PATH)/ARM_CM4F
LD_FILE_GCC ?= ${AT32_SDK_LIB}/cmsis/cm4/device_support/startup/gcc/linker/${MCU_LINKER_NAME}_FLASH.ld
LD_FILE_IAR ?= ${AT32_SDK_LIB}/cmsis/cm4/device_support/startup/iar/linker/${MCU_LINKER_NAME}.icf
flash: flash-atlink

View File

@@ -1,569 +0,0 @@
/**
******************************************************************************
* @file startup_at32f435_437.s
* @brief at32f435_437 devices vector table for gcc toolchain.
* this module performs:
* - set the initial sp
* - set the initial pc == reset_handler,
* - set the vector table entries with the exceptions isr address
* - configure the clock system and the external sram to
* be used as data memory (optional, to be enabled by user)
* - 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.
******************************************************************************
*/
.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:
/* 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 initialization 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 WWDT_IRQHandler /* Window Watchdog Timer */
.word PVM_IRQHandler /* PVM through EXINT Line detect */
.word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXINT line */
.word ERTC_WKUP_IRQHandler /* ERTC Wakeup through the EXINT line */
.word FLASH_IRQHandler /* Flash */
.word CRM_IRQHandler /* CRM */
.word EXINT0_IRQHandler /* EXINT Line 0 */
.word EXINT1_IRQHandler /* EXINT Line 1 */
.word EXINT2_IRQHandler /* EXINT Line 2 */
.word EXINT3_IRQHandler /* EXINT Line 3 */
.word EXINT4_IRQHandler /* EXINT Line 4 */
.word EDMA_Stream1_IRQHandler /* EDMA Stream 1 */
.word EDMA_Stream2_IRQHandler /* EDMA Stream 2 */
.word EDMA_Stream3_IRQHandler /* EDMA Stream 3 */
.word EDMA_Stream4_IRQHandler /* EDMA Stream 4 */
.word EDMA_Stream5_IRQHandler /* EDMA Stream 5 */
.word EDMA_Stream6_IRQHandler /* EDMA Stream 6 */
.word EDMA_Stream7_IRQHandler /* EDMA Stream 7 */
.word ADC1_2_3_IRQHandler /* ADC1 & ADC2 & ADC3 */
.word CAN1_TX_IRQHandler /* CAN1 TX */
.word CAN1_RX0_IRQHandler /* CAN1 RX0 */
.word CAN1_RX1_IRQHandler /* CAN1 RX1 */
.word CAN1_SE_IRQHandler /* CAN1 SE */
.word EXINT9_5_IRQHandler /* EXINT Line [9:5] */
.word TMR1_BRK_TMR9_IRQHandler /* TMR1 Brake and TMR9 */
.word TMR1_OVF_TMR10_IRQHandler /* TMR1 Overflow and TMR10 */
.word TMR1_TRG_HALL_TMR11_IRQHandler /* TMR1 Trigger and hall and TMR11 */
.word TMR1_CH_IRQHandler /* TMR1 Channel */
.word TMR2_GLOBAL_IRQHandler /* TMR2 */
.word TMR3_GLOBAL_IRQHandler /* TMR3 */
.word TMR4_GLOBAL_IRQHandler /* TMR4 */
.word I2C1_EVT_IRQHandler /* I2C1 Event */
.word I2C1_ERR_IRQHandler /* I2C1 Error */
.word I2C2_EVT_IRQHandler /* I2C2 Event */
.word I2C2_ERR_IRQHandler /* I2C2 Error */
.word SPI1_IRQHandler /* SPI1 */
.word SPI2_I2S2EXT_IRQHandler /* SPI2 */
.word USART1_IRQHandler /* USART1 */
.word USART2_IRQHandler /* USART2 */
.word USART3_IRQHandler /* USART3 */
.word EXINT15_10_IRQHandler /* EXINT Line [15:10] */
.word ERTCAlarm_IRQHandler /* RTC Alarm through EXINT Line */
.word OTGFS1_WKUP_IRQHandler /* OTGFS1 Wakeup from suspend */
.word TMR8_BRK_TMR12_IRQHandler /* TMR8 Brake and TMR12 */
.word TMR8_OVF_TMR13_IRQHandler /* TMR8 Overflow and TMR13 */
.word TMR8_TRG_HALL_TMR14_IRQHandler /* TMR8 Trigger and hall and TMR14 */
.word TMR8_CH_IRQHandler /* TMR8 Channel */
.word EDMA_Stream8_IRQHandler /* EDMA Stream 8 */
.word XMC_IRQHandler /* XMC */
.word SDIO1_IRQHandler /* SDIO1 */
.word TMR5_GLOBAL_IRQHandler /* TMR5 */
.word SPI3_I2S3EXT_IRQHandler /* SPI3 */
.word UART4_IRQHandler /* UART4 */
.word UART5_IRQHandler /* UART5 */
.word TMR6_DAC_GLOBAL_IRQHandler /* TMR6 & DAC */
.word TMR7_GLOBAL_IRQHandler /* TMR7 */
.word DMA1_Channel1_IRQHandler /* DMA1 Channel 1 */
.word DMA1_Channel2_IRQHandler /* DMA1 Channel 2 */
.word DMA1_Channel3_IRQHandler /* DMA1 Channel 3 */
.word DMA1_Channel4_IRQHandler /* DMA1 Channel 4 */
.word DMA1_Channel5_IRQHandler /* DMA1 Channel 5 */
.word EMAC_IRQHandler /* EMAC */
.word EMAC_WKUP_IRQHandler /* EMAC Wakeup */
.word CAN2_TX_IRQHandler /* CAN2 TX */
.word CAN2_RX0_IRQHandler /* CAN2 RX0 */
.word CAN2_RX1_IRQHandler /* CAN2 RX1 */
.word CAN2_SE_IRQHandler /* CAN2 SE */
.word OTGFS1_IRQHandler /* OTGFS1 */
.word DMA1_Channel6_IRQHandler /* DMA1 Channel 6 */
.word DMA1_Channel7_IRQHandler /* DMA1 Channel 7 */
.word 0 /* Reserved */
.word USART6_IRQHandler /* USART6 */
.word I2C3_EVT_IRQHandler /* I2C3 Event */
.word I2C3_ERR_IRQHandler /* I2C3 Error */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word OTGFS2_WKUP_IRQHandler /* OTGFS2 Wakeup from suspend */
.word OTGFS2_IRQHandler /* OTGFS2 */
.word DVP_IRQHandler /* DVP */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word FPU_IRQHandler /* FPU */
.word UART7_IRQHandler /* UART7 */
.word UART8_IRQHandler /* UART8 */
.word SPI4_IRQHandler /* SPI4 */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word QSPI2_IRQHandler /* QSPI2 */
.word QSPI1_IRQHandler /* QSPI1 */
.word 0 /* Reserved */
.word DMAMUX_IRQHandler /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word SDIO2_IRQHandler /* SDIO2 */
.word ACC_IRQHandler /* ACC */
.word TMR20_BRK_IRQHandler /* TMR20 Brake */
.word TMR20_OVF_IRQHandler /* TMR20 Overflow */
.word TMR20_TRG_HALL_IRQHandler /* TMR20 Trigger and hall */
.word TMR20_CH_IRQHandler /* TMR20 Channel */
.word DMA2_Channel1_IRQHandler /* DMA2 Channel 1 */
.word DMA2_Channel2_IRQHandler /* DMA2 Channel 2 */
.word DMA2_Channel3_IRQHandler /* DMA2 Channel 3 */
.word DMA2_Channel4_IRQHandler /* DMA2 Channel 4 */
.word DMA2_Channel5_IRQHandler /* DMA2 Channel 5 */
.word DMA2_Channel6_IRQHandler /* DMA2 Channel 6 */
.word DMA2_Channel7_IRQHandler /* DMA2 Channel 7 */
/*******************************************************************************
*
* 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 WWDT_IRQHandler
.thumb_set WWDT_IRQHandler,Default_Handler
.weak PVM_IRQHandler
.thumb_set PVM_IRQHandler,Default_Handler
.weak TAMP_STAMP_IRQHandler
.thumb_set TAMP_STAMP_IRQHandler,Default_Handler
.weak ERTC_WKUP_IRQHandler
.thumb_set ERTC_WKUP_IRQHandler,Default_Handler
.weak FLASH_IRQHandler
.thumb_set FLASH_IRQHandler,Default_Handler
.weak CRM_IRQHandler
.thumb_set CRM_IRQHandler,Default_Handler
.weak EXINT0_IRQHandler
.thumb_set EXINT0_IRQHandler,Default_Handler
.weak EXINT1_IRQHandler
.thumb_set EXINT1_IRQHandler,Default_Handler
.weak EXINT2_IRQHandler
.thumb_set EXINT2_IRQHandler,Default_Handler
.weak EXINT3_IRQHandler
.thumb_set EXINT3_IRQHandler,Default_Handler
.weak EXINT4_IRQHandler
.thumb_set EXINT4_IRQHandler,Default_Handler
.weak EDMA_Stream1_IRQHandler
.thumb_set EDMA_Stream1_IRQHandler,Default_Handler
.weak EDMA_Stream2_IRQHandler
.thumb_set EDMA_Stream2_IRQHandler,Default_Handler
.weak EDMA_Stream3_IRQHandler
.thumb_set EDMA_Stream3_IRQHandler,Default_Handler
.weak EDMA_Stream4_IRQHandler
.thumb_set EDMA_Stream4_IRQHandler,Default_Handler
.weak EDMA_Stream5_IRQHandler
.thumb_set EDMA_Stream5_IRQHandler,Default_Handler
.weak EDMA_Stream6_IRQHandler
.thumb_set EDMA_Stream6_IRQHandler,Default_Handler
.weak EDMA_Stream7_IRQHandler
.thumb_set EDMA_Stream7_IRQHandler,Default_Handler
.weak ADC1_2_3_IRQHandler
.thumb_set ADC1_2_3_IRQHandler,Default_Handler
.weak CAN1_TX_IRQHandler
.thumb_set CAN1_TX_IRQHandler,Default_Handler
.weak CAN1_RX0_IRQHandler
.thumb_set CAN1_RX0_IRQHandler,Default_Handler
.weak CAN1_RX1_IRQHandler
.thumb_set CAN1_RX1_IRQHandler,Default_Handler
.weak CAN1_SE_IRQHandler
.thumb_set CAN1_SE_IRQHandler,Default_Handler
.weak EXINT9_5_IRQHandler
.thumb_set EXINT9_5_IRQHandler,Default_Handler
.weak TMR1_BRK_TMR9_IRQHandler
.thumb_set TMR1_BRK_TMR9_IRQHandler,Default_Handler
.weak TMR1_OVF_TMR10_IRQHandler
.thumb_set TMR1_OVF_TMR10_IRQHandler,Default_Handler
.weak TMR1_TRG_HALL_TMR11_IRQHandler
.thumb_set TMR1_TRG_HALL_TMR11_IRQHandler,Default_Handler
.weak TMR1_CH_IRQHandler
.thumb_set TMR1_CH_IRQHandler,Default_Handler
.weak TMR2_GLOBAL_IRQHandler
.thumb_set TMR2_GLOBAL_IRQHandler,Default_Handler
.weak TMR3_GLOBAL_IRQHandler
.thumb_set TMR3_GLOBAL_IRQHandler,Default_Handler
.weak TMR4_GLOBAL_IRQHandler
.thumb_set TMR4_GLOBAL_IRQHandler,Default_Handler
.weak I2C1_EVT_IRQHandler
.thumb_set I2C1_EVT_IRQHandler,Default_Handler
.weak I2C1_ERR_IRQHandler
.thumb_set I2C1_ERR_IRQHandler,Default_Handler
.weak I2C2_EVT_IRQHandler
.thumb_set I2C2_EVT_IRQHandler,Default_Handler
.weak I2C2_ERR_IRQHandler
.thumb_set I2C2_ERR_IRQHandler,Default_Handler
.weak SPI1_IRQHandler
.thumb_set SPI1_IRQHandler,Default_Handler
.weak SPI2_I2S2EXT_IRQHandler
.thumb_set SPI2_I2S2EXT_IRQHandler,Default_Handler
.weak USART1_IRQHandler
.thumb_set USART1_IRQHandler,Default_Handler
.weak USART2_IRQHandler
.thumb_set USART2_IRQHandler,Default_Handler
.weak USART3_IRQHandler
.thumb_set USART3_IRQHandler,Default_Handler
.weak EXINT15_10_IRQHandler
.thumb_set EXINT15_10_IRQHandler,Default_Handler
.weak ERTCAlarm_IRQHandler
.thumb_set ERTCAlarm_IRQHandler,Default_Handler
.weak OTGFS1_WKUP_IRQHandler
.thumb_set OTGFS1_WKUP_IRQHandler,Default_Handler
.weak TMR8_BRK_TMR12_IRQHandler
.thumb_set TMR8_BRK_TMR12_IRQHandler,Default_Handler
.weak TMR8_OVF_TMR13_IRQHandler
.thumb_set TMR8_OVF_TMR13_IRQHandler,Default_Handler
.weak TMR8_TRG_HALL_TMR14_IRQHandler
.thumb_set TMR8_TRG_HALL_TMR14_IRQHandler,Default_Handler
.weak TMR8_CH_IRQHandler
.thumb_set TMR8_CH_IRQHandler,Default_Handler
.weak EDMA_Stream8_IRQHandler
.thumb_set EDMA_Stream8_IRQHandler,Default_Handler
.weak XMC_IRQHandler
.thumb_set XMC_IRQHandler,Default_Handler
.weak SDIO1_IRQHandler
.thumb_set SDIO1_IRQHandler,Default_Handler
.weak TMR5_GLOBAL_IRQHandler
.thumb_set TMR5_GLOBAL_IRQHandler,Default_Handler
.weak SPI3_I2S3EXT_IRQHandler
.thumb_set SPI3_I2S3EXT_IRQHandler,Default_Handler
.weak UART4_IRQHandler
.thumb_set UART4_IRQHandler,Default_Handler
.weak UART5_IRQHandler
.thumb_set UART5_IRQHandler,Default_Handler
.weak TMR6_DAC_GLOBAL_IRQHandler
.thumb_set TMR6_DAC_GLOBAL_IRQHandler,Default_Handler
.weak TMR7_GLOBAL_IRQHandler
.thumb_set TMR7_GLOBAL_IRQHandler,Default_Handler
.weak DMA1_Channel1_IRQHandler
.thumb_set DMA1_Channel1_IRQHandler,Default_Handler
.weak DMA1_Channel2_IRQHandler
.thumb_set DMA1_Channel2_IRQHandler,Default_Handler
.weak DMA1_Channel3_IRQHandler
.thumb_set DMA1_Channel3_IRQHandler,Default_Handler
.weak DMA1_Channel4_IRQHandler
.thumb_set DMA1_Channel4_IRQHandler,Default_Handler
.weak DMA1_Channel5_IRQHandler
.thumb_set DMA1_Channel5_IRQHandler,Default_Handler
.weak EMAC_IRQHandler
.thumb_set EMAC_IRQHandler,Default_Handler
.weak EMAC_WKUP_IRQHandler
.thumb_set EMAC_WKUP_IRQHandler,Default_Handler
.weak CAN2_TX_IRQHandler
.thumb_set CAN2_TX_IRQHandler,Default_Handler
.weak CAN2_RX0_IRQHandler
.thumb_set CAN2_RX0_IRQHandler ,Default_Handler
.weak CAN2_RX1_IRQHandler
.thumb_set CAN2_RX1_IRQHandler ,Default_Handler
.weak CAN2_SE_IRQHandler
.thumb_set CAN2_SE_IRQHandler,Default_Handler
.weak OTGFS1_IRQHandler
.thumb_set OTGFS1_IRQHandler,Default_Handler
.weak DMA1_Channel6_IRQHandler
.thumb_set DMA1_Channel6_IRQHandler,Default_Handler
.weak DMA1_Channel7_IRQHandler
.thumb_set DMA1_Channel7_IRQHandler,Default_Handler
.weak USART6_IRQHandler
.thumb_set USART6_IRQHandler,Default_Handler
.weak I2C3_EVT_IRQHandler
.thumb_set I2C3_EVT_IRQHandler,Default_Handler
.weak I2C3_ERR_IRQHandler
.thumb_set I2C3_ERR_IRQHandler,Default_Handler
.weak OTGFS2_WKUP_IRQHandler
.thumb_set OTGFS2_WKUP_IRQHandler,Default_Handler
.weak OTGFS2_IRQHandler
.thumb_set OTGFS2_IRQHandler,Default_Handler
.weak DVP_IRQHandler
.thumb_set DVP_IRQHandler,Default_Handler
.weak FPU_IRQHandler
.thumb_set FPU_IRQHandler,Default_Handler
.weak UART7_IRQHandler
.thumb_set UART7_IRQHandler,Default_Handler
.weak UART8_IRQHandler
.thumb_set UART8_IRQHandler,Default_Handler
.weak SPI4_IRQHandler
.thumb_set SPI4_IRQHandler,Default_Handler
.weak QSPI2_IRQHandler
.thumb_set QSPI2_IRQHandler,Default_Handler
.weak QSPI1_IRQHandler
.thumb_set QSPI1_IRQHandler,Default_Handler
.weak DMAMUX_IRQHandler
.thumb_set DMAMUX_IRQHandler ,Default_Handler
.weak SDIO2_IRQHandler
.thumb_set SDIO2_IRQHandler ,Default_Handler
.weak ACC_IRQHandler
.thumb_set ACC_IRQHandler,Default_Handler
.weak TMR20_BRK_IRQHandler
.thumb_set TMR20_BRK_IRQHandler,Default_Handler
.weak TMR20_OVF_IRQHandler
.thumb_set TMR20_OVF_IRQHandler,Default_Handler
.weak TMR20_TRG_HALL_IRQHandler
.thumb_set TMR20_TRG_HALL_IRQHandler,Default_Handler
.weak TMR20_CH_IRQHandler
.thumb_set TMR20_CH_IRQHandler,Default_Handler
.weak DMA2_Channel1_IRQHandler
.thumb_set DMA2_Channel1_IRQHandler,Default_Handler
.weak DMA2_Channel2_IRQHandler
.thumb_set DMA2_Channel2_IRQHandler,Default_Handler
.weak DMA2_Channel3_IRQHandler
.thumb_set DMA2_Channel3_IRQHandler,Default_Handler
.weak DMA2_Channel4_IRQHandler
.thumb_set DMA2_Channel4_IRQHandler,Default_Handler
.weak DMA2_Channel5_IRQHandler
.thumb_set DMA2_Channel5_IRQHandler,Default_Handler
.weak DMA2_Channel6_IRQHandler
.thumb_set DMA2_Channel6_IRQHandler,Default_Handler
.weak DMA2_Channel7_IRQHandler
.thumb_set DMA2_Channel7_IRQHandler,Default_Handler