diff --git a/inc/systick.h b/inc/systick.h index 6dd4390..1944b07 100644 --- a/inc/systick.h +++ b/inc/systick.h @@ -1,47 +1,27 @@ -/*! - \file systick.h - \brief the header file of systick - - \version 2024-02-22, V2.1.0, firmware for GD32E23x -*/ - -/* - Copyright (c) 2024, GigaDevice Semiconductor Inc. - - 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 the copyright holder 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. -*/ - -#ifndef SYSTICK_H -#define SYSTICK_H +/** +* ************************************************************************ + * + * @file systick.h + * @author GD32 + * @brief + * + * ************************************************************************ + * @copyright Copyright (c) 2024 GD32 + * ************************************************************************ + */ +#ifndef SYS_TICK_H +#define SYS_TICK_H #include +/* function declarations */ /* configure systick */ void systick_config(void); -/* delay a time in milliseconds */ -void delay_1ms(uint32_t count); -/* delay decrement */ -void delay_decrement(void); -#endif /* SYSTICK_H */ +/* delay a time in milliseconds */ +void delay_ms(uint32_t count); + +/* delay a time in microseconds */ +void delay_us(uint32_t count); + +#endif /* SYS_TICK_H */ \ No newline at end of file diff --git a/inc/wc_bldc_control.h b/inc/wc_bldc_control.h index 3bfd23d..adcf513 100644 --- a/inc/wc_bldc_control.h +++ b/inc/wc_bldc_control.h @@ -5,6 +5,53 @@ #ifndef WC_BLDC_CONTROL_H #define WC_BLDC_CONTROL_H +#include "gd32e23x.h" + +#define RS485_GPIO_RCU RCU_GPIOA +#define RS485_COM_RCU RCU_USART0 +#define RS485_PORT GPIOA +#define RS485_DI_PIN GPIO_PIN_2 +#define RS485_RO_PIN GPIO_PIN_3 +#define RS485_RE_PIN GPIO_PIN_4 +#define RS485_COM USART0 + +#define GPIO_PORT_SPEED_CTRL GPIOA +#define GPIO_PIN_SPEED_CTRL GPIO_PIN_10 + +#define GPIO_PORT_SPEED_FB GPIOA +#define GPIO_PIN_SPEED_FB GPIO_PIN_9 + +#define GPIO_PORT_DRV_ENABLE GPIOF +#define GPIO_PIN_DRV_ENABLE GPIO_PIN_1 + +#define GPIO_PORT_MOTOR_DIR GPIOF +#define GPIO_PIN_MOTOR_DIR GPIO_PIN_0 + +#define RCU_SPEED_CTL RCU_GPIOA +#define RCU_SPEED_FB RCU_GPIOA +#define RCU_DRV_ENABLE RCU_GPIOF +#define RCU_MOTOR_DIR RCU_GPIOF + +#define TIMER_SPEED_CTL TIMER0 +#define TIMER_CH_SPEED_CTL TIMER_CH_2 +#define RCU_TIMER_SPEED_CTL RCU_TIMER0 + void led_blink_config(void); + + +/* configure RS485 port & RE/DE Pin */ +void rs485_com_config(void); +/* Set transmit enabel */ +void rs485_transmit_enable(void); +/* Set receive enabel */ +void rs485_receive_enable(void); + +void bldc_set_pwm(uint8_t pwm); +void bldc_config(void); +void bldc_enable_set(bit_status status); + + +void timer2_config(void); + #endif //WC_BLDC_CONTROL_H diff --git a/ld/gd_e230f4_gcc.ld b/ld/gd_e230f4_gcc.ld index 361a430..00078a6 100644 --- a/ld/gd_e230f4_gcc.ld +++ b/ld/gd_e230f4_gcc.ld @@ -1,141 +1,56 @@ - -/* Entry Point */ ENTRY(Reset_Handler) -/* Highest address of the user mode stack */ -_estack = 0x20001800; /* end of 6K 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 = 32K - RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 6K +MEMORY { + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 4K } -/* Define output sections */ -SECTIONS -{ - /* The startup code goes first into FLASH */ - .isr_vector : - { - . = ALIGN(4); - KEEP(*(.isr_vector)) /* Startup code */ - . = ALIGN(4); - } >FLASH +_estack = ORIGIN(RAM) + LENGTH(RAM); - /* 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 = .; +SECTIONS { + .isr_vector : { + . = ALIGN(4); + KEEP(*(.isr_vector)) + . = ALIGN(4); } >FLASH + .text : { + . = ALIGN(4); + *(.text) + *(.text*) + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) - .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 + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH - /* used by the startup to initialize data */ - _sidata = LOADADDR(.data); + .rodata : { + . = ALIGN(4); + *(.rodata) + *(.rodata*) + . = ALIGN(4); + } >FLASH - /* 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 */ + _sidata = LOADADDR(.data); + + .data : { + . = ALIGN(4); + _sdata = .; + *(.data) + *(.data*) + . = ALIGN(4); + _edata = .; + } >RAM AT>FLASH . = 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 secion */ - _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(4); - PROVIDE ( end = . ); - PROVIDE ( _end = . ); - . = . + _Min_Heap_Size; - . = . + _Min_Stack_Size; - . = ALIGN(4); - } >RAM - - - - /* Remove information from the standard libraries */ - /DISCARD/ : - { - libc.a ( * ) - libm.a ( * ) - libgcc.a ( * ) - } - .ARM.attributes 0 : { *(.ARM.attributes) } -} + .bss : { + _sbss = .; + *(.bss) + *(.bss*) + . = ALIGN(4); + _ebss = .; + } >RAM +} \ No newline at end of file diff --git a/src/main.c b/src/main.c index ad654bb..970ab42 100644 --- a/src/main.c +++ b/src/main.c @@ -29,6 +29,13 @@ int main(void) // led_config(); led_blink_config(); + rs485_com_config(); + + bldc_config(); + bldc_set_pwm(50); + delay_ms(5000); + bldc_enable_set(SET); + while(1){ } diff --git a/src/systick.c b/src/systick.c index 2056a57..dc4b213 100644 --- a/src/systick.c +++ b/src/systick.c @@ -1,37 +1,14 @@ -/*! - \file systick.c - \brief the systick configuration file - - \version 2024-02-22, V2.1.0, firmware for GD32E23x -*/ - -/* - Copyright (c) 2024, GigaDevice Semiconductor inc. - - 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 the copyright holder 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. -*/ - +/** + * ************************************************************************ + * + * @file systick.c + * @author GD32 + * @brief 通过 SysTick 定时器进行微秒级别和毫秒级别的延时函数 + * + * ************************************************************************ + * @copyright Copyright (c) 2024 GD32 + * ************************************************************************ + */ #include "gd32e23x.h" #include "systick.h" @@ -55,7 +32,6 @@ void systick_config(void) count_1ms = (float)count_1us * 1000; } - /** * ************************************************************************ * @brief delay_us 微秒延时函数 @@ -83,10 +59,8 @@ void delay_us(uint32_t count) SysTick->CTRL &= ~SysTick_CTRL_ENABLE_Msk; //将 SysTick 计数器的当前值清零,以便下次使用 SysTick->VAL = 0x0000U; - } - /** * ************************************************************************ * @brief delay_ms 毫秒延时函数 @@ -114,4 +88,4 @@ void delay_ms(uint32_t count) SysTick->CTRL &= ~SysTick_CTRL_ENABLE_Msk; //将 SysTick 计数器的当前值清零,以便下次使用 SysTick->VAL = 0x0000U; -} +} \ No newline at end of file diff --git a/src/wc_bldc_control.c b/src/wc_bldc_control.c index b9615ea..e7a0bb1 100644 --- a/src/wc_bldc_control.c +++ b/src/wc_bldc_control.c @@ -35,3 +35,193 @@ void led_blink_config(void){ nvic_irq_enable(TIMER13_IRQn, 0); timer_enable(TIMER13); } + +/*! + \brief configure RS485 port & RE/DE Pin + \param[in] none + \param[out] none + \retval none +*/ +void rs485_com_config(void) +{ + rcu_periph_clock_enable(RS485_GPIO_RCU); + rcu_periph_clock_enable(RS485_COM_RCU); + + gpio_af_set(RS485_PORT, GPIO_AF_1, RS485_RO_PIN | RS485_DI_PIN); + + /* configure USART Tx as alternate function push-pull */ + gpio_mode_set(RS485_PORT, GPIO_MODE_AF, GPIO_PUPD_PULLUP, RS485_DI_PIN); + gpio_output_options_set(RS485_PORT, GPIO_OTYPE_PP, GPIO_OSPEED_10MHZ, RS485_DI_PIN); + + gpio_mode_set(RS485_PORT, GPIO_MODE_AF, GPIO_PUPD_PULLUP, RS485_RO_PIN); + gpio_output_options_set(RS485_PORT, GPIO_OTYPE_PP, GPIO_OSPEED_10MHZ, RS485_RO_PIN); + + /* USART configure */ + usart_deinit(RS485_COM); + usart_baudrate_set(RS485_COM, 115200U); + usart_receive_config(RS485_COM, USART_RECEIVE_ENABLE); + usart_transmit_config(RS485_COM, USART_TRANSMIT_ENABLE); + + usart_enable(RS485_COM); + + gpio_mode_set(RS485_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, RS485_RE_PIN); + gpio_output_options_set(RS485_PORT, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, RS485_RE_PIN); + + gpio_bit_write(RS485_PORT, RS485_RE_PIN, SET); +} + +void rs485_transmit_enable(void) +{ + gpio_bit_write(RS485_PORT, RS485_RE_PIN, SET); +} + +void rs485_receive_enable(void) +{ + gpio_bit_write(RS485_PORT, RS485_RE_PIN, RESET); +} + +uint8_t speed_pwm = 0; //bldc default pwm is 30 + +void bldc_set_pwm(uint8_t pwm) +{ + if (pwm > 0 && pwm <= 100) + { + speed_pwm = pwm; + timer_channel_output_pulse_value_config(TIMER0, TIMER_CH_2, 12*speed_pwm); + } +} + +void bldc_config(void) +{ + rcu_periph_clock_enable(RCU_SPEED_CTL | RCU_SPEED_FB); + rcu_periph_clock_enable(RCU_DRV_ENABLE | RCU_MOTOR_DIR); + + /* ------------------------------ + -----BLDC speed control GPIO----- + -----GPIOA_10 -- */ + gpio_mode_set(GPIO_PORT_SPEED_CTRL, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_SPEED_CTRL); + gpio_output_options_set(GPIO_PORT_SPEED_CTRL, GPIO_OTYPE_OD, GPIO_OSPEED_50MHZ, GPIO_PIN_SPEED_CTRL); + gpio_af_set(GPIO_PORT_SPEED_CTRL, GPIO_AF_2, GPIO_PIN_SPEED_CTRL); + + /* ------------------------------ + -----BLDC speed report GPIO------ + -----GPIOA_9 --- */ + // gpio_mode_set(GPIO_PORT_SPEED_FB, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_SPEED_FB); + // gpio_output_options_set(GPIO_PORT_SPEED_FB, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, GPIO_PIN_SPEED_FB); + // gpio_af_set(GPIO_PORT_SPEED_FB, GPIO_AF_2, GPIO_PIN_SPEED_FB); + + /* ------------------------------ + -----BLDC enable GPIO------------ + -----GPIOF_1 --------- */ + gpio_mode_set(GPIO_PORT_DRV_ENABLE, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO_PIN_DRV_ENABLE); + gpio_output_options_set(GPIO_PORT_DRV_ENABLE, GPIO_OTYPE_OD, GPIO_OSPEED_50MHZ, GPIO_PIN_DRV_ENABLE); + gpio_bit_reset(GPIO_PORT_DRV_ENABLE, GPIO_PIN_DRV_ENABLE); + + /* ------------------------------ + -----BLDC forward/reverse GPIO--- + -----GPIOF_0 --- + -----no need control for --- + ----- WM7040-24V*/ + gpio_mode_set(GPIO_PORT_MOTOR_DIR, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO_PIN_MOTOR_DIR); + gpio_output_options_set(GPIO_PORT_MOTOR_DIR, GPIO_OTYPE_OD, GPIO_OSPEED_50MHZ, GPIO_PIN_MOTOR_DIR); + gpio_bit_set(GPIO_PORT_MOTOR_DIR, GPIO_PIN_MOTOR_DIR); + + // gpio_bit_write(GPIOA, GPIO_PIN_10, RESET); + + timer_parameter_struct timer_initpara; + timer_oc_parameter_struct timer_ocinitpara; + // timer_ic_parameter_struct timer_icinitpara; + + rcu_periph_clock_enable(RCU_TIMER_SPEED_CTL); + timer_deinit(TIMER_SPEED_CTL); + + timer_struct_para_init(&timer_initpara); + timer_initpara.prescaler =59; + timer_initpara.alignedmode =TIMER_COUNTER_EDGE; + timer_initpara.counterdirection =TIMER_COUNTER_UP; + timer_initpara.period =1199; + timer_initpara.clockdivision =TIMER_CKDIV_DIV1; + timer_init(TIMER_SPEED_CTL, &timer_initpara); + + timer_channel_output_struct_para_init(&timer_ocinitpara); + timer_ocinitpara.outputstate =TIMER_CCX_ENABLE; + timer_ocinitpara.outputnstate =TIMER_CCXN_DISABLE; + timer_ocinitpara.ocpolarity =TIMER_OC_POLARITY_HIGH; + timer_ocinitpara.ocnpolarity =TIMER_OCN_POLARITY_HIGH; + timer_ocinitpara.ocidlestate =TIMER_OC_IDLE_STATE_LOW; + timer_ocinitpara.ocnidlestate =TIMER_OCN_IDLE_STATE_LOW; + timer_channel_output_config(TIMER_SPEED_CTL, TIMER_CH_SPEED_CTL, &timer_ocinitpara); + + timer_channel_output_pulse_value_config(TIMER_SPEED_CTL, TIMER_CH_SPEED_CTL, 12* speed_pwm); + timer_channel_output_mode_config(TIMER_SPEED_CTL, TIMER_CH_SPEED_CTL, TIMER_OC_MODE_PWM0); + timer_channel_output_shadow_config(TIMER_SPEED_CTL, TIMER_CH_SPEED_CTL, TIMER_OC_SHADOW_DISABLE); + + timer_primary_output_config(TIMER_SPEED_CTL, ENABLE); + timer_auto_reload_shadow_enable(TIMER_SPEED_CTL); + + timer_enable(TIMER_SPEED_CTL); + + nvic_irq_enable(TIMER0_Channel_IRQn, 1); +} + +void bldc_enable_set(bit_status status) +{ + gpio_bit_write(GPIOF, GPIO_PIN_1, status); +} + +void timer2_config(void) +{ + rcu_periph_clock_enable(RCU_GPIOA); + rcu_periph_clock_enable(RCU_CFGCMP); + + gpio_mode_set(GPIOA, GPIO_MODE_INPUT, GPIO_PUPD_NONE, GPIO_PIN_9); + + nvic_irq_enable(EXTI4_15_IRQn, 2U); + + syscfg_exti_line_config(EXTI_SOURCE_GPIOA, EXTI_SOURCE_PIN9); + exti_init(EXTI_9, EXTI_INTERRUPT, EXTI_TRIG_FALLING); + exti_interrupt_flag_clear(EXTI_9); + + gpio_mode_set(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_6); + gpio_output_options_set(GPIOA, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ,GPIO_PIN_6); + gpio_af_set(GPIOA, GPIO_AF_1, GPIO_PIN_6); + + timer_ic_parameter_struct timer_icinitpara; + timer_parameter_struct timer_initpara; + + /* enable the TIMER clock */ + rcu_periph_clock_enable(RCU_TIMER2); + /* disable a TIMER */ + timer_deinit(TIMER2); + /* initialize TIMER init parameter struct */ + timer_struct_para_init(&timer_initpara); + /* TIMER2 configuration */ + timer_initpara.prescaler = 71; + timer_initpara.alignedmode = TIMER_COUNTER_EDGE; + timer_initpara.counterdirection = TIMER_COUNTER_UP; + timer_initpara.period = 65535; + timer_initpara.clockdivision = TIMER_CKDIV_DIV1; + timer_init(TIMER2, &timer_initpara); + + /* TIMER2 configuration */ + /* initialize TIMER channel input parameter struct */ + timer_channel_input_struct_para_init(&timer_icinitpara); + /* TIMER2 CH0 input capture configuration */ + timer_icinitpara.icpolarity = TIMER_IC_POLARITY_RISING; + timer_icinitpara.icselection = TIMER_IC_SELECTION_DIRECTTI; + timer_icinitpara.icprescaler = TIMER_IC_PSC_DIV1; + timer_icinitpara.icfilter = 0x0; + timer_input_capture_config(TIMER2,TIMER_CH_0,&timer_icinitpara); + + /* auto-reload preload enable */ + timer_auto_reload_shadow_enable(TIMER2); + /* clear channel 0 interrupt bit */ + timer_interrupt_flag_clear(TIMER2,TIMER_INT_FLAG_CH0); + /* channel 0 interrupt enable */ + timer_interrupt_enable(TIMER2,TIMER_INT_CH0); + + /* TIMER2 counter enable */ + timer_enable(TIMER2); + + nvic_irq_enable(TIMER2_IRQn, 3U); +} diff --git a/startup/startup_gd32e23x.S b/startup/startup_gd32e23x.S index a1accc0..18e7846 100644 --- a/startup/startup_gd32e23x.S +++ b/startup/startup_gd32e23x.S @@ -1,232 +1,164 @@ - .syntax unified - .cpu cortex-m23 - .fpu softvfp - .thumb +/****************************************************************************** + * @file startup_gd32e230k8t6.s + * @brief CMSIS-Core Device Startup File for Cortex-M23 Device GD32E230K8T6 + * @version V2.2.0 + * @date 26. May 2021 + ******************************************************************************/ -.global g_pfnVectors -.global Default_Handler + .syntax unified + .arch armv8-m.base + .fpu softvfp + .thumb -/* necessary symbols defined in linker script to initialize data */ -.word _sidata -.word _sdata -.word _edata -.word _sbss -.word _ebss + .global g_pfnVectors + .global Default_Handler - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function - -/* reset Handler */ + .word _sidata + .word _sdata + .word _edata + .word _sbss + .word _ebss +/* Reset_Handler */ + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function Reset_Handler: - ldr r0, =_estack - mov sp, r0 -/* copy the data segment into ram */ - movs r1, #0 - b LoopCopyDataInit + ldr r0, =_estack + msr psp, r0 + ldr r0, =_sdata + ldr r1, =_edata + ldr r2, =_sidata + movs r3, #0 + b LoopCopyDataInit CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - + ldr r4, [r2, r3] + str r4, [r0, r3] + adds r3, r3, #4 LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss - + adds r4, r0, r3 + cmp r4, r1 + bcc CopyDataInit + + ldr r2, =_sbss + ldr r4, =_ebss + movs r3, #0 + b LoopFillZerobss FillZerobss: - movs r3, #0 - str r3, [r2] - adds r2, r2, #4 - + str r3, [r2] + adds r2, r2, #4 LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss + cmp r2, r4 + bcc FillZerobss -/* Call SystemInit function */ - bl SystemInit -/* Call static constructors */ - bl __libc_init_array -/*Call the main function */ - bl main - -LoopForever: - b LoopForever - -.size Reset_Handler, .-Reset_Handler - -.section .text.Default_Handler,"ax",%progbits + bl SystemInit + bl main + bx lr + .size Reset_Handler, .-Reset_Handler +/* Default_Handler */ + .section .text.Default_Handler,"ax",%progbits Default_Handler: Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/* Vector Table */ + .section .isr_vector,"a",%progbits + .type g_pfnVectors,%object + .size g_pfnVectors, .-g_pfnVectors +g_pfnVectors: + .word _estack + .word Reset_Handler - .section .vectors,"a",%progbits - .global __gVectors + .word NMI_Handler /* -14 NMI Handler */ + .word HardFault_Handler /* -13 Hard Fault Handler */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word SVC_Handler /* -5 SVCall Handler */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word PendSV_Handler /* -2 PendSV Handler */ + .word SysTick_Handler /* -1 SysTick Handler */ -__gVectors: - .word _sp /* Top of Stack */ - .word Reset_Handler /* 1:Reset Handler */ - .word NMI_Handler /* 2:NMI Handler */ - .word HardFault_Handler /* 3:Hard Fault Handler */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word SVC_Handler /* 11:SVCall Handler */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word PendSV_Handler /* 14:PendSV Handler */ - .word SysTick_Handler /* 15:SysTick Handler */ + .word WWDGT_IRQHandler + .word LVD_IRQHandler + .word RTC_IRQHandler + .word FMC_IRQHandler + .word RCU_IRQHandler + .word EXTI0_1_IRQHandler + .word EXTI2_3_IRQHandler + .word EXTI4_15_IRQHandler + .word 0 + .word DMA_Channel0_IRQHandler + .word DMA_Channel1_2_IRQHandler + .word DMA_Channel3_4_IRQHandler + .word ADC_CMP_IRQHandler + .word TIMER0_BRK_UP_TRG_COM_IRQHandler + .word TIMER0_Channel_IRQHandler + .word 0 + .word TIMER2_IRQHandler + .word TIMER5_IRQHandler + .word 0 + .word TIMER13_IRQHandler + .word TIMER14_IRQHandler + .word TIMER15_IRQHandler + .word TIMER16_IRQHandler + .word I2C0_EV_IRQHandler + .word I2C1_EV_IRQHandler + .word SPI0_IRQHandler + .word SPI1_IRQHandler + .word USART0_IRQHandler + .word USART1_IRQHandler + .word 0 + .word 0 + .word 0 + .word I2C0_ER_IRQHandler + .word 0 + .word I2C1_ER_IRQHandler - /* external interrupts handler */ - .word WWDGT_IRQHandler /* 16:Window Watchdog Timer */ - .word LVD_IRQHandler /* 17:LVD through EXTI Line detect */ - .word RTC_IRQHandler /* 18:RTC through EXTI Line */ - .word FMC_IRQHandler /* 19:FMC */ - .word RCU_IRQHandler /* 20:RCU */ - .word EXTI0_1_IRQHandler /* 21:EXTI Line 0 and EXTI Line 1 */ - .word EXTI2_3_IRQHandler /* 22:EXTI Line 2 and EXTI Line 3 */ - .word EXTI4_15_IRQHandler /* 23:EXTI Line 4 to EXTI Line 15 */ - .word 0 /* Reserved */ - .word DMA_Channel0_IRQHandler /* 25:DMA Channel 0 */ - .word DMA_Channel1_2_IRQHandler /* 26:DMA Channel 1 and DMA Channel 2 */ - .word DMA_Channel3_4_IRQHandler /* 27:DMA Channel 3 and DMA Channel 4 */ - .word ADC_CMP_IRQHandler /* 28:ADC and Comparator */ - .word TIMER0_BRK_UP_TRG_COM_IRQHandler /* 29:TIMER0 Break,Update,Trigger and Commutation */ - .word TIMER0_Channel_IRQHandler /* 30:TIMER0 Channel Capture Compare */ - .word 0 /* Reserved */ - .word TIMER2_IRQHandler /* 32:TIMER2 */ - .word TIMER5_IRQHandler /* 33:TIMER5 */ - .word 0 /* Reserved */ - .word TIMER13_IRQHandler /* 35:TIMER13 */ - .word TIMER14_IRQHandler /* 36:TIMER14 */ - .word TIMER15_IRQHandler /* 37:TIMER15 */ - .word TIMER16_IRQHandler /* 38:TIMER16 */ - .word I2C0_EV_IRQHandler /* 39:I2C0 Event */ - .word I2C1_EV_IRQHandler /* 40:I2C1 Event */ - .word SPI0_IRQHandler /* 41:SPI0 */ - .word SPI1_IRQHandler /* 42:SPI1 */ - .word USART0_IRQHandler /* 43:USART0 */ - .word USART1_IRQHandler /* 44:USART1 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word I2C0_ER_IRQHandler /* 48:I2C0 Error */ - .word 0 /* Reserved */ - .word I2C1_ER_IRQHandler /* 50:I2C1 Error */ - - .size __gVectors, . - __gVectors - - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDGT_IRQHandler - .thumb_set WWDGT_IRQHandler,Default_Handler - - .weak LVD_IRQHandler - .thumb_set LVD_IRQHandler,Default_Handler - - .weak TAMPER_IRQHandler - .thumb_set TAMPER_IRQHandler,Default_Handler - - .weak RTC_IRQHandler - .thumb_set RTC_IRQHandler,Default_Handler - - .weak FMC_IRQHandler - .thumb_set FMC_IRQHandler,Default_Handler - - .weak RCU_IRQHandler - .thumb_set RCU_IRQHandler,Default_Handler - - .weak EXTI0_1_IRQHandler - .thumb_set EXTI0_1_IRQHandler,Default_Handler - - .weak EXTI2_3_IRQHandler - .thumb_set EXTI2_3_IRQHandler,Default_Handler - - .weak EXTI4_15_IRQHandler - .thumb_set EXTI4_15_IRQHandler,Default_Handler - - .weak DMA_Channel0_IRQHandler - .thumb_set DMA_Channel0_IRQHandler,Default_Handler - - .weak DMA_Channel1_2_IRQHandler - .thumb_set DMA_Channel1_2_IRQHandler,Default_Handler - - .weak DMA_Channel3_4_IRQHandler - .thumb_set DMA_Channel3_4_IRQHandler,Default_Handler - - .weak ADC_CMP_IRQHandler - .thumb_set ADC_CMP_IRQHandler,Default_Handler - - .weak TIMER0_BRK_UP_TRG_COM_IRQHandler - .thumb_set TIMER0_BRK_UP_TRG_COM_IRQHandler,Default_Handler - - .weak TIMER0_Channel_IRQHandler - .thumb_set TIMER0_Channel_IRQHandler,Default_Handler - - .weak TIMER2_IRQHandler - .thumb_set TIMER2_IRQHandler,Default_Handler - - .weak TIMER5_IRQHandler - .thumb_set TIMER5_IRQHandler,Default_Handler - - .weak TIMER13_IRQHandler - .thumb_set TIMER13_IRQHandler,Default_Handler - - .weak TIMER14_IRQHandler - .thumb_set TIMER14_IRQHandler,Default_Handler - - .weak TIMER15_IRQHandler - .thumb_set TIMER15_IRQHandler,Default_Handler - - .weak TIMER16_IRQHandler - .thumb_set TIMER16_IRQHandler,Default_Handler - - .weak I2C0_EV_IRQHandler - .thumb_set I2C0_EV_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak SPI0_IRQHandler - .thumb_set SPI0_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak USART0_IRQHandler - .thumb_set USART0_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak I2C0_ER_IRQHandler - .thumb_set I2C0_ER_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler +.macro Set_Default_Handler Handler_Name +.weak \Handler_Name +.set \Handler_Name, Default_Handler +.endm +/* + Set_Default_Handler NMI_Handler + Set_Default_Handler HardFault_Handler + Set_Default_Handler SVC_Handler + Set_Default_Handler PendSV_Handler + Set_Default_Handler SysTick_Handler +*/ + + Set_Default_Handler WWDGT_IRQHandler + Set_Default_Handler LVD_IRQHandler + Set_Default_Handler RTC_IRQHandler + Set_Default_Handler FMC_IRQHandler + Set_Default_Handler RCU_IRQHandler + Set_Default_Handler EXTI0_1_IRQHandler + Set_Default_Handler EXTI2_3_IRQHandler + Set_Default_Handler EXTI4_15_IRQHandler + Set_Default_Handler DMA_Channel0_IRQHandler + Set_Default_Handler DMA_Channel1_2_IRQHandler + Set_Default_Handler DMA_Channel3_4_IRQHandler + Set_Default_Handler ADC_CMP_IRQHandler + Set_Default_Handler TIMER0_BRK_UP_TRG_COM_IRQHandler + Set_Default_Handler TIMER0_Channel_IRQHandler + Set_Default_Handler TIMER2_IRQHandler + Set_Default_Handler TIMER5_IRQHandler + Set_Default_Handler TIMER13_IRQHandler + Set_Default_Handler TIMER14_IRQHandler + Set_Default_Handler TIMER15_IRQHandler + Set_Default_Handler TIMER16_IRQHandler + Set_Default_Handler I2C0_EV_IRQHandler + Set_Default_Handler I2C1_EV_IRQHandler + Set_Default_Handler SPI0_IRQHandler + Set_Default_Handler SPI1_IRQHandler + Set_Default_Handler USART0_IRQHandler + Set_Default_Handler USART1_IRQHandler + Set_Default_Handler I2C0_ER_IRQHandler + Set_Default_Handler I2C1_ER_IRQHandler +.end \ No newline at end of file