From 74be33dfbc06852cf56fdad1fea2df0b7b02a5b4 Mon Sep 17 00:00:00 2001 From: J Blackman Date: Tue, 31 Jan 2023 11:31:23 +1100 Subject: [PATCH] AT32 development, introduction of AT32F435 target (#12247) * AT32F435: new target (#12159) * AT32F435: New target (WIP) * IO and Timer Updates * Adding pseudonyms for the STM TypeDef items. - implementation to follow * Adding config_streamer support for AT32 * Implementation for IO * Adding in Peripheral mapping from emsr. * Warnings cleanup for AT drivers * Getting things to the linking stage * Add AT-START-F435 LEDs as default in AT32F435 as a temporary measure to aid bringup * Remove tabs * Enable selection of serial port to use for MSP * Setup defaults for AT-START-F435 to use MSP on UART1 * Fix for most recent 4.5.0 Makefile changes * Solve for sanity check. * Add AT32F435 MCU type * Fix compilation issue with SITL * Merge conflict resolution * Minor cleanup * Adding line feed. --------- Co-authored-by: Steve Evans --- Makefile | 2 +- .../drivers/inc/at32f435_437_rcc_periph.h | 87 ++ .../AT32F43x/drivers/src/at32f435_437_crm.c | 2 +- .../AT32F43x/drivers/src/at32f435_437_qspi.c | 1 + .../AT32F43x/drivers/src/at32f435_437_usb.c | 1 + make/mcu/AT32F4.mk | 0 src/link/at32_flash_f43xM.ld | 48 ++ src/link/at32_flash_f4_split.ld | 249 ++++++ src/main/build/build_config.c | 2 + src/main/build/build_config.h | 1 + src/main/cli/cli.c | 3 +- src/main/config/config_streamer.c | 18 + src/main/drivers/at32/bus_spi_at32bsp.c | 400 +++++++++ src/main/drivers/at32/dma_at32f43x.c | 102 +++ src/main/drivers/at32/dma_atbsp.h | 91 ++ src/main/drivers/at32/persistent_at32bsp.c | 66 ++ src/main/drivers/at32/pwm_output_at32bsp.c | 293 +++++++ src/main/drivers/at32/serial_uart_at32bsp.c | 283 +++++++ src/main/drivers/at32/serial_uart_at32f43x.c | 331 ++++++++ src/main/drivers/at32/system_at32f43x.c | 123 +++ src/main/drivers/at32/timer_at32bsp.c | 770 +++++++++++++++++ src/main/drivers/at32/timer_at32f43x.c | 144 ++++ src/main/drivers/at32/timer_def_at32.h | 406 +++++++++ src/main/drivers/bus_spi.c | 31 +- src/main/drivers/bus_spi.h | 6 + src/main/drivers/bus_spi_impl.h | 6 +- src/main/drivers/bus_spi_pinconfig.c | 96 ++- src/main/drivers/dma.h | 27 +- src/main/drivers/dma_reqmap.c | 169 +++- src/main/drivers/dma_reqmap.h | 5 + src/main/drivers/exti.c | 60 +- src/main/drivers/io.c | 79 +- src/main/drivers/io.h | 36 +- src/main/drivers/nvic.h | 5 + src/main/drivers/rcc.c | 64 ++ src/main/drivers/rcc.h | 37 +- src/main/drivers/serial_uart.c | 28 +- src/main/drivers/serial_uart.h | 4 + src/main/drivers/serial_uart_impl.h | 29 +- src/main/drivers/system.c | 8 +- src/main/drivers/timer.c | 1 + src/main/drivers/timer.h | 18 +- src/main/fc/init.c | 2 +- src/main/io/flashfs.c | 3 + src/main/io/serial.c | 10 +- src/main/io/serial.h | 1 - src/main/platform.h | 52 ++ src/main/startup/at32/at32f435_437.h | 779 ++++++++++++++++++ src/main/startup/at32/at32f435_437_clock.c | 117 +++ src/main/startup/at32/at32f435_437_clock.h | 44 + src/main/startup/at32/at32f435_437_conf.h | 180 ++++ src/main/startup/at32/startup_at32f435_437.s | 571 +++++++++++++ src/main/startup/at32/system_at32f435_437.c | 186 +++++ src/main/startup/at32/system_at32f435_437.h | 75 ++ src/main/target/AT32F435/target.c | 22 + src/main/target/AT32F435/target.h | 105 +++ src/main/target/AT32F435/target.mk | 41 + src/main/target/common_pre.h | 20 +- 58 files changed, 6256 insertions(+), 84 deletions(-) create mode 100644 lib/main/AT32F43x/drivers/inc/at32f435_437_rcc_periph.h create mode 100644 make/mcu/AT32F4.mk create mode 100644 src/link/at32_flash_f43xM.ld create mode 100644 src/link/at32_flash_f4_split.ld create mode 100644 src/main/drivers/at32/bus_spi_at32bsp.c create mode 100644 src/main/drivers/at32/dma_at32f43x.c create mode 100644 src/main/drivers/at32/dma_atbsp.h create mode 100644 src/main/drivers/at32/persistent_at32bsp.c create mode 100644 src/main/drivers/at32/pwm_output_at32bsp.c create mode 100644 src/main/drivers/at32/serial_uart_at32bsp.c create mode 100644 src/main/drivers/at32/serial_uart_at32f43x.c create mode 100644 src/main/drivers/at32/system_at32f43x.c create mode 100644 src/main/drivers/at32/timer_at32bsp.c create mode 100644 src/main/drivers/at32/timer_at32f43x.c create mode 100644 src/main/drivers/at32/timer_def_at32.h create mode 100644 src/main/startup/at32/at32f435_437.h create mode 100644 src/main/startup/at32/at32f435_437_clock.c create mode 100644 src/main/startup/at32/at32f435_437_clock.h create mode 100644 src/main/startup/at32/at32f435_437_conf.h create mode 100644 src/main/startup/at32/startup_at32f435_437.s create mode 100644 src/main/startup/at32/system_at32f435_437.c create mode 100644 src/main/startup/at32/system_at32f435_437.h create mode 100644 src/main/target/AT32F435/target.c create mode 100644 src/main/target/AT32F435/target.h create mode 100644 src/main/target/AT32F435/target.mk diff --git a/Makefile b/Makefile index 1379d929da..cb57c8f712 100644 --- a/Makefile +++ b/Makefile @@ -376,7 +376,7 @@ $(TARGET_BIN): $(TARGET_UNPATCHED_BIN) $(V1) cat $(TARGET_UNPATCHED_BIN).md5 | awk '{printf("%08x: %s",64-16,$$2);}' | xxd -r - $(TARGET_EXST_HASH_SECTION_FILE) # For some currently unknown reason, OBJCOPY, with only input/output files, will generate a file around 2GB for the H730 unless we remove an unused-section -# As a workaround drop the ._user_heap_stack section, which is only used during build to show errors if there's not enough space for the heap/stack. +# As a workaround drop the ._user_heap_stack section, which is only used during build to show errors if there's not enough space for the heap/stack. # The issue can be seen with `readelf -S $(TARGET_EXST_ELF)' vs `readelf -S $(TARGET_ELF)` $(V1) @echo "Patching updated HASH section into $(TARGET_EXST_ELF)" "$(STDOUT)" $(OBJCOPY) $(TARGET_ELF) $(TARGET_EXST_ELF) --remove-section ._user_heap_stack --update-section .exst_hash=$(TARGET_EXST_HASH_SECTION_FILE) diff --git a/lib/main/AT32F43x/drivers/inc/at32f435_437_rcc_periph.h b/lib/main/AT32F43x/drivers/inc/at32f435_437_rcc_periph.h new file mode 100644 index 0000000000..bff2131004 --- /dev/null +++ b/lib/main/AT32F43x/drivers/inc/at32f435_437_rcc_periph.h @@ -0,0 +1,87 @@ +/* + * rcc_at32f43x_periph.h + * + * Created on: 2022年3月19日 + * Author: emsr + * 仿照hal 库,为at32 各外设直接定义对应的使能、重置位 + * offset= log2(mask) + */ + +#ifndef MAIN_DRIVERS_RCC_AT32F43X_PERIPH_H_ +#define MAIN_DRIVERS_RCC_AT32F43X_PERIPH_H_ + + +/******************** Bit definition for AT32F437 CRM PERIPH MASK ***************/ +/* AHB offset 0x30 */ +#define CRM_AHB1_GPIOA_PER_MASK ((uint32_t)0x00000001) /*!< gpiob periph clock */ +#define CRM_AHB1_GPIOB_PER_MASK ((uint32_t)0x00000002) /*!< gpiob periph clock */ +#define CRM_AHB1_GPIOC_PER_MASK ((uint32_t)0x00000004) /*!< gpioc periph clock */ +#define CRM_AHB1_GPIOD_PER_MASK ((uint32_t)0x00000008) /*!< gpiod periph clock */ +#define CRM_AHB1_GPIOE_PER_MASK ((uint32_t)0x00000010) /*!< gpioe periph clock */ +#define CRM_AHB1_GPIOF_PER_MASK ((uint32_t)0x00000020) /*!< gpiof periph clock */ +#define CRM_AHB1_GPIOG_PER_MASK ((uint32_t)0x00000040) /*!< gpiog periph clock */ +#define CRM_AHB1_GPIOH_PER_MASK ((uint32_t)0x00000080) /*!< gpioh periph clock */ +#define CRM_AHB1_CRC_PER_MASK ((uint32_t)0x00001000) /*!< crc periph clock */ +#define CRM_AHB1_EDMA_PER_MASK ((uint32_t)0x00200000) /*!< edma periph clock */ +#define CRM_AHB1_DMA1_PER_MASK ((uint32_t)0x00400000) /*!< dma1 periph clock */ +#define CRM_AHB1_DMA2_PER_MASK ((uint32_t)0x01000000) /*!< dma2 periph clock */ +#define CRM_AHB1_EMAC_PER_MASK ((uint32_t)0x02000000) /*!< emac periph clock */ +#define CRM_AHB1_EMACTX_PER_MASK ((uint32_t)0x04000000) /*!< emac tx periph clock */ +#define CRM_AHB1_EMACRX_PER_MASK ((uint32_t)0x08000000) /*!< emac rx periph clock */ +#define CRM_AHB1_EMACPTP_PER_MASK ((uint32_t)0x10000000) /*!< emac ptp periph clock */ +#define CRM_AHB1_OTGFS2_PER_MASK ((uint32_t)0x20000000) /*!< otgfs2 periph clock */ + /* ahb periph2 offset 0x34*/ +#define CRM_AHB2_DVP_PER_MASK ((uint32_t)0x00000001) /*!< dvp periph clock */ +#define CRM_AHB2_OTGFS1_PER_MASK ((uint32_t)0x00000080) /*!< otgfs1 periph clock */ +#define CRM_AHB2_SDIO1_PER_MASK ((uint32_t)0x00008000) /*!< sdio1 periph clock */ + /* ahb periph3 offset 0x38 */ +#define CRM_AHB3_XMC_PER_MASK ((uint32_t)0x00000001) /*!< xmc periph clock */ +#define CRM_AHB3_QSPI1_PER_MASK ((uint32_t)0x00000002) /*!< qspi1 periph clock */ +#define CRM_AHB3_QSPI2_PER_MASK ((uint32_t)0x00004000) /*!< qspi2 periph clock */ +#define CRM_AHB3_SDIO2_PER_MASK ((uint32_t)0x00008000) /*!< sdio2 periph clock */ + /* apb1 periph offset 0x40 */ +#define CRM_APB1_TMR2_PER_MASK ((uint32_t)0x00000001) /*!< tmr2 periph clock */ +#define CRM_APB1_TMR3_PER_MASK ((uint32_t)0x00000002) /*!< tmr3 periph clock */ +#define CRM_APB1_TMR4_PER_MASK ((uint32_t)0x00000004) /*!< tmr4 periph clock */ +#define CRM_APB1_TMR5_PER_MASK ((uint32_t)0x00000008) /*!< tmr5 periph clock */ +#define CRM_APB1_TMR6_PER_MASK ((uint32_t)0x00000010) /*!< tmr6 periph clock */ +#define CRM_APB1_TMR7_PER_MASK ((uint32_t)0x00000020) /*!< tmr7 periph clock */ +#define CRM_APB1_TMR12_PER_MASK ((uint32_t)0x00000040) /*!< tmr12 periph clock */ +#define CRM_APB1_TMR13_PER_MASK ((uint32_t)0x00000080) /*!< tmr13 periph clock */ +#define CRM_APB1_TMR14_PER_MASK ((uint32_t)0x00000100) /*!< tmr14 periph clock */ +#define CRM_APB1_WWDT_PER_MASK ((uint32_t)0x00000800) /*!< wwdt periph clock */ +#define CRM_APB1_SPI2_PER_MASK ((uint32_t)0x00004000) /*!< spi2 periph clock */ +#define CRM_APB1_SPI3_PER_MASK ((uint32_t)0x00008000) /*!< spi3 periph clock */ +#define CRM_APB1_USART2_PER_MASK ((uint32_t)0x00020000) /*!< usart2 periph clock */ +#define CRM_APB1_USART3_PER_MASK ((uint32_t)0x00040000) /*!< usart3 periph clock */ +#define CRM_APB1_UART4_PER_MASK ((uint32_t)0x00080000) /*!< uart4 periph clock */ +#define CRM_APB1_UART5_PER_MASK ((uint32_t)0x00100000) /*!< uart5 periph clock */ +#define CRM_APB1_I2C1_PER_MASK ((uint32_t)0x00200000) /*!< i2c1 periph clock */ +#define CRM_APB1_I2C2_PER_MASK ((uint32_t)0x00400000) /*!< i2c2 periph clock */ +#define CRM_APB1_I2C3_PER_MASK ((uint32_t)0x00800000) /*!< i2c3 periph clock */ +#define CRM_APB1_CAN1_PER_MASK ((uint32_t)0x02000000) /*!< can1 periph clock */ +#define CRM_APB1_CAN2_PER_MASK ((uint32_t)0x04000000) /*!< can2 periph clock */ +#define CRM_APB1_PWC_PER_MASK ((uint32_t)0x10000000) /*!< pwc periph clock */ +#define CRM_APB1_DAC_PER_MASK ((uint32_t)0x20000000) /*!< dac periph clock */ +#define CRM_APB1_UART7_PER_MASK ((uint32_t)0x40000000) /*!< uart7 periph clock */ +#define CRM_APB1_UART8_PER_MASK ((uint32_t)0x80000000) /*!< uart8 periph clock */ + /* apb2 periph offset 0x44 */ +#define CRM_APB2_TMR1_PER_MASK ((uint32_t)0x00000001) /*!< tmr1 periph clock */ +#define CRM_APB2_TMR8_PER_MASK ((uint32_t)0x00000002) /*!< tmr8 periph clock */ +#define CRM_APB2_USART1_PER_MASK ((uint32_t)0x00000010) /*!< usart1 periph clock */ +#define CRM_APB2_USART6_PER_MASK ((uint32_t)0x00000020) /*!< usart6 periph clock */ +#define CRM_APB2_ADC1_PER_MASK ((uint32_t)0x00000100) /*!< adc1 periph clock */ +#define CRM_APB2_ADC2_PER_MASK ((uint32_t)0x00000200) /*!< adc2 periph clock */ +#define CRM_APB2_ADC3_PER_MASK ((uint32_t)0x00000400) /*!< adc3 periph clock */ +#define CRM_APB2_SPI1_PER_MASK ((uint32_t)0x00001000) /*!< spi1 periph clock */ +#define CRM_APB2_SPI4_PER_MASK ((uint32_t)0x00002000) /*!< spi4 periph clock */ +#define CRM_APB2_SCFG_PER_MASK ((uint32_t)0x00004000) /*!< scfg periph clock */ +#define CRM_APB2_TMR9_PER_MASK ((uint32_t)0x00010000) /*!< tmr9 periph clock */ +#define CRM_APB2_TMR10_PER_MASK ((uint32_t)0x00020000) /*!< tmr10 periph clock */ +#define CRM_APB2_TMR11_PER_MASK ((uint32_t)0x00040000) /*!< tmr11 periph clock */ +#define CRM_APB2_TMR20_PER_MASK ((uint32_t)0x00100000) /*!< tmr20 periph clock */ +#define CRM_APB2_ACC_PER_MASK ((uint32_t)0x20000000) /*!< acc periph clock */ + + + +#endif /* MAIN_DRIVERS_RCC_AT32F43X_PERIPH_H_ */ diff --git a/lib/main/AT32F43x/drivers/src/at32f435_437_crm.c b/lib/main/AT32F43x/drivers/src/at32f435_437_crm.c index c123f1a30f..21e2be041b 100644 --- a/lib/main/AT32F43x/drivers/src/at32f435_437_crm.c +++ b/lib/main/AT32F43x/drivers/src/at32f435_437_crm.c @@ -936,7 +936,7 @@ error_status crm_pll_parameter_calculate(crm_pll_clock_source_type pll_rcs, uint } /* polling pll parameters */ - for(ms = ms_min; ms <= ms_max; ms ++) + for(ms = ms_min; ms <= (int32_t)ms_max; ms ++) { for(fr = 5; fr >= 0; fr --) { diff --git a/lib/main/AT32F43x/drivers/src/at32f435_437_qspi.c b/lib/main/AT32F43x/drivers/src/at32f435_437_qspi.c index 9a2a97380c..0e570015e2 100644 --- a/lib/main/AT32F43x/drivers/src/at32f435_437_qspi.c +++ b/lib/main/AT32F43x/drivers/src/at32f435_437_qspi.c @@ -165,6 +165,7 @@ flag_status qspi_flag_get(qspi_type* qspi_x, uint32_t flag) */ void qspi_flag_clear(qspi_type* qspi_x, uint32_t flag) { + (void)flag; qspi_x->cmdsts = QSPI_CMDSTS_FLAG; } diff --git a/lib/main/AT32F43x/drivers/src/at32f435_437_usb.c b/lib/main/AT32F43x/drivers/src/at32f435_437_usb.c index 2440ccdadb..bb178cdfa3 100644 --- a/lib/main/AT32F43x/drivers/src/at32f435_437_usb.c +++ b/lib/main/AT32F43x/drivers/src/at32f435_437_usb.c @@ -442,6 +442,7 @@ void usb_write_packet(otg_global_type *usbx, uint8_t *pusr_buf, uint16_t num, ui */ void usb_read_packet(otg_global_type *usbx, uint8_t *pusr_buf, uint16_t num, uint16_t nbytes) { + (void)num; uint32_t n_index; uint32_t nhbytes = (nbytes + 3) / 4; uint32_t *pbuf = (uint32_t *)pusr_buf; diff --git a/make/mcu/AT32F4.mk b/make/mcu/AT32F4.mk new file mode 100644 index 0000000000..e69de29bb2 diff --git a/src/link/at32_flash_f43xM.ld b/src/link/at32_flash_f43xM.ld new file mode 100644 index 0000000000..457028bc62 --- /dev/null +++ b/src/link/at32_flash_f43xM.ld @@ -0,0 +1,48 @@ +/* +***************************************************************************** +** +** File : at32_flash_f43xM.ld +** +** Abstract : Linker script for AT32F435/7xM Device with +** 4032KByte 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 +** +***************************************************************************** +*/ + + +/* + FLASH : 0x0800 0000 -- 0x083E FFFF + MEM : 0x2000 0000 -- 0x2007 FFFF + +*/ + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K + FLASH_CDEF (r) : ORIGIN = 0x08002800, LENGTH = 6K + FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K + FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 3984K: 4000K + FLASH_CDEF_EXT (r) : ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x083EC000 : 0x083F0000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 16K : 0K + + SYSTEM_MEMORY (rx) : ORIGIN = 0x1FFF0000, LENGTH = 16K + RAM1 (xrw) : ORIGIN = 0x10000000, LENGTH = 64K + RAM (xrw) : ORIGIN = 0x20010000, LENGTH = 128K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K /* external ram */ +} + +REGION_ALIAS("STACKRAM", RAM) +REGION_ALIAS("FASTRAM", RAM1) +REGION_ALIAS("VECTAB", RAM1) + +REGION_ALIAS("MOVABLE_FLASH", FLASH1) + +INCLUDE "at32_flash_f4_split.ld" diff --git a/src/link/at32_flash_f4_split.ld b/src/link/at32_flash_f4_split.ld new file mode 100644 index 0000000000..5700510aa8 --- /dev/null +++ b/src/link/at32_flash_f4_split.ld @@ -0,0 +1,249 @@ +/* +***************************************************************************** +** +** File : at32_flash_f4_split.ld +** +** Abstract : Common linker script for STM32 devices. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_Hot_Reboot_Flags_Size = 16; +_estack = ORIGIN(STACKRAM) + LENGTH(STACKRAM) - _Hot_Reboot_Flags_Size; /* end of RAM */ + +/* Base address where the config is stored. */ +__config_start = ORIGIN(FLASH_CONFIG); +__config_end = ORIGIN(FLASH_CONFIG) + LENGTH(FLASH_CONFIG); + +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x800; /* required amount of stack */ + +/* Define output sections */ +SECTIONS +{ + /* + * The ISR vector table is loaded at the beginning of the FLASH, + * But it is linked (space reserved) at the beginning of the VECTAB region, + * which is aliased either to FLASH or RAM. + * When linked to RAM, the table can optionally be copied from FLASH to RAM + * for table relocation. + */ + + _isr_vector_table_flash_base = LOADADDR(.isr_vector); + PROVIDE (isr_vector_table_flash_base = _isr_vector_table_flash_base); + + .isr_vector : + { + . = ALIGN(4); + PROVIDE (isr_vector_table_base = .); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + PROVIDE (isr_vector_table_end = .); + } >FLASH + + /* System memory (read-only bootloader) interrupt vector */ + .system_isr_vector (NOLOAD) : + { + . = ALIGN(4); + PROVIDE (system_isr_vector_table_base = .); + KEEP(*(.system_isr_vector)) /* Bootloader code */ + . = ALIGN(4); + } >SYSTEM_MEMORY + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + *(.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 */ + } >FLASH1 + + /* + Critical program code goes into RAM1 + */ + tcm_code = LOADADDR(.tcm_code); + .tcm_code : + { + . = ALIGN(4); + tcm_code_start = .; + *(.tcm_code) + *(.tcm_code*) + . = ALIGN(4); + tcm_code_end = .; + } >RAM1 AT >FLASH1 + + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >MOVABLE_FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >MOVABLE_FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >MOVABLE_FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(.fini_array*)) + KEEP (*(SORT(.fini_array.*))) + PROVIDE_HIDDEN (__fini_array_end = .); + } >MOVABLE_FLASH + .pg_registry : + { + PROVIDE_HIDDEN (__pg_registry_start = .); + KEEP (*(.pg_registry)) + KEEP (*(SORT(.pg_registry.*))) + PROVIDE_HIDDEN (__pg_registry_end = .); + } >MOVABLE_FLASH + .pg_resetdata : + { + PROVIDE_HIDDEN (__pg_resetdata_start = .); + KEEP (*(.pg_resetdata)) + PROVIDE_HIDDEN (__pg_resetdata_end = .); + } >FLASH1 + + /* Storage for the address for the configuration section so we can grab it out of the hex file */ + .custom_defaults : + { + . = ALIGN(4); + KEEP (*(.custom_defaults_start_address)) + . = ALIGN(4); + KEEP (*(.custom_defaults_end_address)) + . = ALIGN(4); + __custom_defaults_internal_start = .; + KEEP (*(.custom_defaults)) + . = ALIGN(4); + } >FLASH_CDEF + + PROVIDE_HIDDEN (__custom_defaults_start = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? ORIGIN(FLASH_CDEF_EXT) : __custom_defaults_internal_start); + PROVIDE_HIDDEN (__custom_defaults_end = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? ORIGIN(FLASH_CDEF_EXT) + LENGTH(FLASH_CDEF_EXT) : ORIGIN(FLASH_CDEF) + LENGTH(FLASH_CDEF)); + + /* 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> MOVABLE_FLASH + + /* Uninitialized data section */ + . = ALIGN(4); + .bss (NOLOAD) : + { + /* 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) + *(SORT_BY_ALIGNMENT(.bss*)) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* used during startup to initialized fastram_data */ + _sfastram_idata = LOADADDR(.fastram_data); + + /* Initialized FAST_DATA section for unsuspecting developers */ + .fastram_data : + { + . = ALIGN(4); + _sfastram_data = .; /* create a global symbol at data start */ + *(.fastram_data) /* .data sections */ + *(.fastram_data*) /* .data* sections */ + + . = ALIGN(4); + _efastram_data = .; /* define a global symbol at data end */ + } >FASTRAM AT> FLASH1 + + . = ALIGN(4); + .fastram_bss (NOLOAD) : + { + _sfastram_bss = .; + __fastram_bss_start__ = _sfastram_bss; + *(.fastram_bss) + *(SORT_BY_ALIGNMENT(.fastram_bss*)) + + . = ALIGN(4); + _efastram_bss = .; + __fastram_bss_end__ = _efastram_bss; + } >FASTRAM + + .persistent_data (NOLOAD) : + { + __persistent_data_start__ = .; + *(.persistent_data) + . = ALIGN(4); + __persistent_data_end__ = .; + } >FASTRAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + _heap_stack_end = ORIGIN(STACKRAM) + LENGTH(STACKRAM) - _Hot_Reboot_Flags_Size; + _heap_stack_begin = _heap_stack_end - _Min_Stack_Size - _Min_Heap_Size; + . = _heap_stack_begin; + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >STACKRAM = 0xa5 + + /* MEMORY_bank1 section, code must be located here explicitly */ + /* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */ + .memory_b1_text : + { + *(.mb1text) /* .mb1text sections (code) */ + *(.mb1text*) /* .mb1text* sections (code) */ + *(.mb1rodata) /* read-only data (constants) */ + *(.mb1rodata*) + } >MEMORY_B1 + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/src/main/build/build_config.c b/src/main/build/build_config.c index d607ce9f70..5788d22883 100644 --- a/src/main/build/build_config.c +++ b/src/main/build/build_config.c @@ -68,6 +68,8 @@ mcuTypeId_e getMcuTypeId(void) return MCU_TYPE_H723_725; #elif defined(STM32G474xx) return MCU_TYPE_G474; +#elif defined (AT32F435) + return MCU_TYPE_AT32; #else return MCU_TYPE_UNKNOWN; #endif diff --git a/src/main/build/build_config.h b/src/main/build/build_config.h index cec7d9ac5f..52811118a5 100644 --- a/src/main/build/build_config.h +++ b/src/main/build/build_config.h @@ -59,6 +59,7 @@ typedef enum { MCU_TYPE_H723_725, MCU_TYPE_G474, MCU_TYPE_H730, + MCU_TYPE_AT32, MCU_TYPE_UNKNOWN = 255, } mcuTypeId_e; diff --git a/src/main/cli/cli.c b/src/main/cli/cli.c index 95208d7c59..94bb7fd363 100644 --- a/src/main/cli/cli.c +++ b/src/main/cli/cli.c @@ -301,6 +301,7 @@ static const char *mcuTypeNames[] = { "H723/H725", "G474", "H730", + "AT32F435" }; static const char *configurationStates[] = { "UNCONFIGURED", "CUSTOM DEFAULTS", "CONFIGURED" }; @@ -2484,7 +2485,7 @@ static void cliFlashInfo(const char *cmdName, char *cmdline) } #endif // USE_FLASH_CHIP -#ifdef USE_FLASHFS +#if defined(USE_FLASHFS) && defined(USE_FLASH_CHIP) static void cliFlashErase(const char *cmdName, char *cmdline) { UNUSED(cmdName); diff --git a/src/main/config/config_streamer.c b/src/main/config/config_streamer.c index b66c1ba793..674119b158 100644 --- a/src/main/config/config_streamer.c +++ b/src/main/config/config_streamer.c @@ -93,6 +93,8 @@ void config_streamer_start(config_streamer_t *c, uintptr_t base, int size) #elif defined(CONFIG_IN_FLASH) || defined(CONFIG_IN_FILE) #if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) HAL_FLASH_Unlock(); +#elif defined(AT32F4) + flash_unlock(); #else FLASH_Unlock(); #endif @@ -111,6 +113,8 @@ void config_streamer_start(config_streamer_t *c, uintptr_t base, int size) // NOP #elif defined(STM32G4) // NOP +#elif defined(AT32F4) + flash_flag_clear(FLASH_ODF_FLAG | FLASH_PRGMERR_FLAG | FLASH_EPPERR_FLAG); #elif defined(UNIT_TEST) || defined(SIMULATOR_BUILD) // NOP #else @@ -492,6 +496,18 @@ static int write_word(config_streamer_t *c, config_streamer_buffer_align_type_t if (status != HAL_OK) { return -2; } +#elif defined(AT32F4) + if (c->address % FLASH_PAGE_SIZE == 0) { + const flash_status_type status = flash_sector_erase(c->address); + if (status != FLASH_OPERATE_DONE) { + return -1; + } + } + + const flash_status_type status = flash_word_program(c->address, (uint32_t)*buffer); + if (status != FLASH_OPERATE_DONE) { + return -2; + } #else // !STM32H7 && !STM32F7 && !STM32G4 if (c->address % FLASH_PAGE_SIZE == 0) { const FLASH_Status status = FLASH_EraseSector(getFLASHSectorForEEPROM(), VoltageRange_3); //0x08080000 to 0x080A0000 @@ -553,6 +569,8 @@ int config_streamer_finish(config_streamer_t *c) #elif defined(CONFIG_IN_FLASH) #if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) HAL_FLASH_Lock(); +#elif defined(AT32F4) + flash_lock(); #else FLASH_Lock(); #endif diff --git a/src/main/drivers/at32/bus_spi_at32bsp.c b/src/main/drivers/at32/bus_spi_at32bsp.c new file mode 100644 index 0000000000..91782c7a47 --- /dev/null +++ b/src/main/drivers/at32/bus_spi_at32bsp.c @@ -0,0 +1,400 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include +#include +#include + +#include "platform.h" + +#ifdef USE_SPI + +#define IS_CCM(p) (((uint32_t)p & 0xffff0000) == 0x10000000) + +#include "common/maths.h" +#include "drivers/bus.h" +#include "drivers/bus_spi.h" +#include "drivers/bus_spi_impl.h" +#include "drivers/exti.h" +#include "drivers/io.h" +#include "drivers/rcc.h" + +static spi_init_type defaultInit = { + .master_slave_mode = SPI_MODE_MASTER, + .transmission_mode = SPI_TRANSMIT_FULL_DUPLEX, + .frame_bit_num = SPI_FRAME_8BIT, + .cs_mode_selection = SPI_CS_SOFTWARE_MODE, + .first_bit_transmission = SPI_FIRST_BIT_MSB, + .mclk_freq_division = SPI_MCLK_DIV_8, + .clock_polarity = SPI_CLOCK_POLARITY_HIGH, + .clock_phase = SPI_CLOCK_PHASE_2EDGE +}; + +static uint16_t spiDivisorToBRbits(spi_type *instance, uint16_t divisor) +{ + UNUSED(instance); + divisor = constrain(divisor, 2, 256); + return (ffs(divisor) - 2) << 3; // SPI_CR1_BR_Pos + +} + +static void spiSetDivisorBRreg(spi_type *instance, uint16_t divisor) +{ +#define BR_BITS ((BIT(5) | BIT(4) | BIT(3))) + const uint16_t tempRegister = (instance->ctrl1 & ~BR_BITS); + instance->ctrl1 = tempRegister | spiDivisorToBRbits(instance, divisor); +#undef BR_BITS +} + +void spiInitDevice(SPIDevice device) +{ + spiDevice_t *spi = &(spiDevice[device]); + + if (!spi->dev) { + return; + } + + // Enable SPI clock + RCC_ClockCmd(spi->rcc, ENABLE); + RCC_ResetCmd(spi->rcc, ENABLE); + + IOInit(IOGetByTag(spi->sck), OWNER_SPI_SCK, RESOURCE_INDEX(device)); + IOInit(IOGetByTag(spi->miso), OWNER_SPI_MISO, RESOURCE_INDEX(device)); + IOInit(IOGetByTag(spi->mosi), OWNER_SPI_MOSI, RESOURCE_INDEX(device)); + + IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG_HIGH, spi->sckAF); + IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG, spi->misoAF); + IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->mosiAF); + + // Init SPI hardware + spi_i2s_reset(spi->dev); + + spi_i2s_dma_transmitter_enable(spi->dev,TRUE); + spi_i2s_dma_receiver_enable(spi->dev,TRUE); + + spi_init(spi->dev,&defaultInit); + spi_crc_polynomial_set(spi->dev,7); + + spi_enable(spi->dev,TRUE); +} + +void spiInternalResetDescriptors(busDevice_t *bus) +{ + dma_init_type *initTx = bus->initTx; + + dma_default_para_init(initTx); + + initTx->direction=DMA_DIR_MEMORY_TO_PERIPHERAL; + initTx->loop_mode_enable=FALSE; + initTx->peripheral_base_addr=(uint32_t)&bus->busType_u.spi.instance->dt ; + initTx->priority =DMA_PRIORITY_LOW; + initTx->peripheral_inc_enable =FALSE; + initTx->peripheral_data_width = DMA_PERIPHERAL_DATA_WIDTH_BYTE; + initTx->memory_data_width = DMA_MEMORY_DATA_WIDTH_BYTE; + + if (bus->dmaRx) { + dma_init_type *initRx = bus->initRx; + + dma_default_para_init(initRx); + + initRx->direction = DMA_DIR_PERIPHERAL_TO_MEMORY; + initRx->loop_mode_enable = FALSE; + initRx->peripheral_base_addr = (uint32_t)&bus->busType_u.spi.instance->dt; + initRx->priority = DMA_PRIORITY_LOW; + initRx->peripheral_inc_enable = FALSE; + initRx->peripheral_data_width = DMA_PERIPHERAL_DATA_WIDTH_BYTE; + + } +} + +void spiInternalResetStream(dmaChannelDescriptor_t *descriptor) +{ + DMA_ARCH_TYPE *streamRegs = (DMA_ARCH_TYPE *)descriptor->ref; + xDMA_Cmd(streamRegs, FALSE); + DMA_CLEAR_FLAG(descriptor, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF); +} + +static bool spiInternalReadWriteBufPolled(spi_type *instance, const uint8_t *txData, uint8_t *rxData, int len) +{ + uint8_t b; + + while (len--) { + b = txData ? *(txData++) : 0xFF; + + while(spi_i2s_flag_get(instance,SPI_I2S_TDBE_FLAG) == RESET); + spi_i2s_data_transmit(instance,b); + + + while(spi_i2s_flag_get(instance,SPI_I2S_RDBF_FLAG) == RESET); + b=spi_i2s_data_receive(instance); + + if (rxData) { + *(rxData++) = b; + } + } + + return true; +} + +void spiInternalInitStream(const extDevice_t *dev, bool preInit) +{ + STATIC_DMA_DATA_AUTO uint8_t dummyTxByte = 0xff; + STATIC_DMA_DATA_AUTO uint8_t dummyRxByte; + busDevice_t *bus = dev->bus; + + volatile busSegment_t *segment = bus->curSegment; + + if (preInit) { + // Prepare the init structure for the next segment to reduce inter-segment interval + segment++; + if(segment->len == 0) { + // There's no following segment + return; + } + } + + int len = segment->len; + + uint8_t *txData = segment->u.buffers.txData; + dma_init_type *initTx = bus->initTx; + + if (txData) { + initTx->memory_base_addr = (uint32_t)txData; + initTx->memory_inc_enable =TRUE; + } else { + dummyTxByte = 0xff; + initTx->memory_base_addr = (uint32_t)&dummyTxByte; + initTx->memory_inc_enable =FALSE; + } + initTx->buffer_size =len; + + if (dev->bus->dmaRx) { + uint8_t *rxData = segment->u.buffers.rxData; + dma_init_type *initRx = bus->initRx; + + if (rxData) { + initRx->memory_base_addr= (uint32_t)rxData; + initRx->memory_inc_enable = TRUE; + } else { + initRx->memory_base_addr = (uint32_t)&dummyRxByte; + initRx->memory_inc_enable = FALSE; + } + + initRx->buffer_size = len; + } +} + +void spiInternalStartDMA(const extDevice_t *dev) +{ + dmaChannelDescriptor_t *dmaTx = dev->bus->dmaTx; + dmaChannelDescriptor_t *dmaRx = dev->bus->dmaRx; + DMA_ARCH_TYPE *streamRegsTx = (DMA_ARCH_TYPE *)dmaTx->ref; + if (dmaRx) { + DMA_ARCH_TYPE *streamRegsRx = (DMA_ARCH_TYPE *)dmaRx->ref; + + // Use the correct callback argument + dmaRx->userParam = (uint32_t)dev; + + // Clear transfer flags + DMA_CLEAR_FLAG(dmaTx, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF); + DMA_CLEAR_FLAG(dmaRx, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF); + + // Disable streams to enable update + xDMA_Cmd(streamRegsTx, FALSE); + xDMA_Cmd(streamRegsRx, FALSE); + + xDMA_ITConfig(streamRegsRx, DMA_IT_TCIF, TRUE); + + // Update streams + xDMA_Init(streamRegsTx, dev->bus->initTx); + xDMA_Init(streamRegsRx, dev->bus->initRx); + + // Enable streams + xDMA_Cmd(streamRegsTx, TRUE); + xDMA_Cmd(streamRegsRx, TRUE); + + spi_i2s_dma_transmitter_enable(dev->bus->busType_u.spi.instance, TRUE); + spi_i2s_dma_receiver_enable(dev->bus->busType_u.spi.instance, TRUE); + + } else { + // Use the correct callback argument + dmaTx->userParam = (uint32_t)dev; + + // Clear transfer flags + DMA_CLEAR_FLAG(dmaTx, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF); + + // Disable stream to enable update + xDMA_Cmd(streamRegsTx, FALSE); + + // Update stream + xDMA_Init(streamRegsTx, dev->bus->initTx); + + // Enable stream + xDMA_Cmd(streamRegsTx, TRUE); + xDMA_ITConfig(streamRegsTx, DMA_IT_TCIF, TRUE); + + /* Enable the SPI DMA Tx request */ + spi_i2s_dma_transmitter_enable(dev->bus->busType_u.spi.instance, TRUE); + } +} + +void spiInternalStopDMA (const extDevice_t *dev) +{ + dmaChannelDescriptor_t *dmaTx = dev->bus->dmaTx; + dmaChannelDescriptor_t *dmaRx = dev->bus->dmaRx; + spi_type *instance = dev->bus->busType_u.spi.instance; + DMA_ARCH_TYPE *streamRegsTx = (DMA_ARCH_TYPE *)dmaTx->ref; + + if (dmaRx) { + DMA_ARCH_TYPE *streamRegsRx = (DMA_ARCH_TYPE *)dmaRx->ref; + + // Disable streams + xDMA_Cmd(streamRegsTx, FALSE); + xDMA_Cmd(streamRegsRx, FALSE); + + DMA_CLEAR_FLAG(dmaTx, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF); + DMA_CLEAR_FLAG(dmaRx, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF); + + spi_i2s_dma_transmitter_enable(instance, FALSE); + spi_i2s_dma_receiver_enable(instance, FALSE); + } else { + // Ensure the current transmission is complete + while(spi_i2s_flag_get(instance,SPI_I2S_BF_FLAG)); + + // Drain the RX buffer + while(spi_i2s_flag_get(instance,SPI_I2S_RDBF_FLAG)) { + instance->dt; + } + + // Disable stream + xDMA_Cmd(streamRegsTx, FALSE); + DMA_CLEAR_FLAG(dmaTx, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF); + + spi_i2s_dma_transmitter_enable(instance, FALSE); + } +} + +// DMA transfer setup and start +void spiSequenceStart(const extDevice_t *dev) +{ + busDevice_t *bus = dev->bus; + spi_type *instance = bus->busType_u.spi.instance; + bool dmaSafe = dev->useDMA; + uint32_t xferLen = 0; + uint32_t segmentCount = 0; + + dev->bus->initSegment = true; + + spi_enable(instance, FALSE); + + // Switch bus speed + if (dev->busType_u.spi.speed != bus->busType_u.spi.speed) { + spiSetDivisorBRreg(bus->busType_u.spi.instance, dev->busType_u.spi.speed); + bus->busType_u.spi.speed = dev->busType_u.spi.speed; + } + + if (dev->busType_u.spi.leadingEdge != bus->busType_u.spi.leadingEdge) { + if (dev->busType_u.spi.leadingEdge) { + instance->ctrl1_bit.clkpol = SPI_CLOCK_POLARITY_LOW; + instance->ctrl1_bit.clkpha = SPI_CLOCK_PHASE_1EDGE; + } else { + instance->ctrl1_bit.clkpol = SPI_CLOCK_POLARITY_HIGH; + instance->ctrl1_bit.clkpha = SPI_CLOCK_PHASE_2EDGE; + } + bus->busType_u.spi.leadingEdge = dev->busType_u.spi.leadingEdge; + } + + spi_enable(instance,TRUE); + + // Check that any there are no attempts to DMA to/from CCD SRAM + for (busSegment_t *checkSegment = (busSegment_t *)bus->curSegment; checkSegment->len; checkSegment++) { + // Check there is no receive data as only transmit DMA is available + if (((checkSegment->u.buffers.rxData) && (IS_CCM(checkSegment->u.buffers.rxData) || + (bus->dmaRx == (dmaChannelDescriptor_t *)NULL))) || + ((checkSegment->u.buffers.txData) && IS_CCM(checkSegment->u.buffers.txData))) { + dmaSafe = false; + break; + } + // Note that these counts are only valid if dmaSafe is true + segmentCount++; + xferLen += checkSegment->len; + } + // Use DMA if possible + // If there are more than one segments, or a single segment with negateCS negated then force DMA irrespective of length + if (bus->useDMA && dmaSafe && ((segmentCount > 1) || (xferLen >= 8) || !bus->curSegment->negateCS)) { + spiInternalInitStream(dev, false); + IOLo(dev->busType_u.spi.csnPin); + spiInternalStartDMA(dev); + } else { + busSegment_t *lastSegment = NULL; + + while (bus->curSegment->len) { + if (!lastSegment || lastSegment->negateCS) { + IOLo(dev->busType_u.spi.csnPin); + } + + spiInternalReadWriteBufPolled( + bus->busType_u.spi.instance, + bus->curSegment->u.buffers.txData, + bus->curSegment->u.buffers.rxData, + bus->curSegment->len + ); + + if (bus->curSegment->negateCS) { + IOHi(dev->busType_u.spi.csnPin); + } + + if (bus->curSegment->callback) { + switch(bus->curSegment->callback(dev->callbackArg)) { + case BUS_BUSY: + bus->curSegment--; + break; + + case BUS_ABORT: + bus->curSegment = (busSegment_t *)BUS_SPI_FREE; + return; + + case BUS_READY: + default: + break; + } + } + lastSegment = (busSegment_t *)bus->curSegment; + bus->curSegment++; + } + + if (lastSegment && !lastSegment->negateCS) { + IOHi(dev->busType_u.spi.csnPin); + } + + // If a following transaction has been linked, start it + if (bus->curSegment->u.link.dev) { + const extDevice_t *nextDev = bus->curSegment->u.link.dev; + busSegment_t *nextSegments = (busSegment_t *)bus->curSegment->u.link.segments; + busSegment_t *endSegment = (busSegment_t *)bus->curSegment; + bus->curSegment = nextSegments; + endSegment->u.link.dev = NULL; + spiSequenceStart(nextDev); + } else { + bus->curSegment = (busSegment_t *)BUS_SPI_FREE; + } + } +} +#endif diff --git a/src/main/drivers/at32/dma_at32f43x.c b/src/main/drivers/at32/dma_at32f43x.c new file mode 100644 index 0000000000..e3f3d9863c --- /dev/null +++ b/src/main/drivers/at32/dma_at32f43x.c @@ -0,0 +1,102 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include +#include +#include + +#include "platform.h" + +#ifdef USE_DMA + +#include "drivers/nvic.h" +#include "drivers/dma.h" +#include "drivers/rcc.h" +#include "drivers/resource.h" + +/* + * DMA descriptors. + */ +dmaChannelDescriptor_t dmaDescriptors[DMA_LAST_HANDLER] = { + DEFINE_DMA_CHANNEL(DMA1, 1, 0), + DEFINE_DMA_CHANNEL(DMA1, 2, 4), + DEFINE_DMA_CHANNEL(DMA1, 3, 8), + DEFINE_DMA_CHANNEL(DMA1, 4, 12), + DEFINE_DMA_CHANNEL(DMA1, 5, 16), + DEFINE_DMA_CHANNEL(DMA1, 6, 20), + DEFINE_DMA_CHANNEL(DMA1, 7, 24), + + DEFINE_DMA_CHANNEL(DMA2, 1, 0), + DEFINE_DMA_CHANNEL(DMA2, 2, 4), + DEFINE_DMA_CHANNEL(DMA2, 3, 8), + DEFINE_DMA_CHANNEL(DMA2, 4, 12), + DEFINE_DMA_CHANNEL(DMA2, 5, 16), + DEFINE_DMA_CHANNEL(DMA2, 6, 20), + DEFINE_DMA_CHANNEL(DMA2, 7, 24), +}; + +/* + * DMA IRQ Handlers + */ +DEFINE_DMA_IRQ_HANDLER(1, 1, DMA1_CH1_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 2, DMA1_CH2_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 3, DMA1_CH3_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 4, DMA1_CH4_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 5, DMA1_CH5_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 6, DMA1_CH6_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 7, DMA1_CH7_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 1, DMA2_CH1_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 2, DMA2_CH2_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 3, DMA2_CH3_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 4, DMA2_CH4_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 5, DMA2_CH5_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 6, DMA2_CH6_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 7, DMA2_CH7_HANDLER) + +static void enableDmaClock(int index) +{ + RCC_ClockCmd(dmaDescriptors[index].dma == DMA1 ? RCC_AHB1(DMA1) : RCC_AHB1(DMA2), ENABLE); + dmamux_enable(dmaDescriptors[index].dma,TRUE); +} + +void dmaEnable(dmaIdentifier_e identifier) +{ + const int index = DMA_IDENTIFIER_TO_INDEX(identifier); + + enableDmaClock(index); +} + +void dmaMuxEnable(dmaIdentifier_e identifier, uint32_t dmaMuxId) +{ + const int index = DMA_IDENTIFIER_TO_INDEX(identifier); + dmamux_init(dmaDescriptors[index].dmamux, dmaMuxId); +} + +void dmaSetHandler(dmaIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam) +{ + const int index = DMA_IDENTIFIER_TO_INDEX(identifier); + + enableDmaClock(index); + dmaDescriptors[index].irqHandlerCallback = callback; + dmaDescriptors[index].userParam = userParam; + + nvic_irq_enable(dmaDescriptors[index].irqN, NVIC_PRIORITY_BASE(priority), NVIC_PRIORITY_SUB(priority)); +} +#endif diff --git a/src/main/drivers/at32/dma_atbsp.h b/src/main/drivers/at32/dma_atbsp.h new file mode 100644 index 0000000000..49b452558e --- /dev/null +++ b/src/main/drivers/at32/dma_atbsp.h @@ -0,0 +1,91 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +#include "platform.h" +#include "drivers/resource.h" + +typedef enum { + DMA_NONE = 0, + DMA1_CH1_HANDLER = 1, + DMA1_CH2_HANDLER, + DMA1_CH3_HANDLER, + DMA1_CH4_HANDLER, + DMA1_CH5_HANDLER, + DMA1_CH6_HANDLER, + DMA1_CH7_HANDLER, + DMA2_CH1_HANDLER, + DMA2_CH2_HANDLER, + DMA2_CH3_HANDLER, + DMA2_CH4_HANDLER, + DMA2_CH5_HANDLER, + DMA2_CH6_HANDLER, + DMA2_CH7_HANDLER, + DMA_LAST_HANDLER = DMA2_CH7_HANDLER +} dmaIdentifier_e; + +#define DMA_DEVICE_NO(x) ((((x)-1) / 7) + 1) +#define DMA_DEVICE_INDEX(x) ((((x)-1) % 7) + 1) + +uint32_t dmaGetChannel(const uint8_t channel); + +#define DMA_OUTPUT_INDEX 0 +#define DMA_OUTPUT_STRING "DMA%d Channel %d:" +#define DMA_INPUT_STRING "DMA%d_CH%d" + +#define DEFINE_DMA_CHANNEL(d, c, f) { \ + .dma = d, \ + .ref = (dmaResource_t *)d ## _CHANNEL ## c ##_BASE, \ + .irqHandlerCallback = NULL, \ + .flagsShift = f, \ + .irqN = d ## _Channel ## c ## _IRQn, \ + .userParam = 0, \ + .owner.owner = 0, \ + .owner.resourceIndex = 0 ,\ + .dmamux= (dmamux_channel_type *) d ## MUX_CHANNEL ##c \ + } + +#define DEFINE_DMA_IRQ_HANDLER(d, c, i) DMA_HANDLER_CODE void DMA ## d ## _Channel ## c ## _IRQHandler(void) {\ + const uint8_t index = DMA_IDENTIFIER_TO_INDEX(i); \ + dmaCallbackHandlerFuncPtr handler = dmaDescriptors[index].irqHandlerCallback; \ + if (handler) \ + handler(&dmaDescriptors[index]); \ + } + +#define DMA_CLEAR_FLAG(d, flag) d->dma->clr = (flag << d->flagsShift) +#define DMA_GET_FLAG_STATUS(d, flag) (d->dma->sts & (flag << d->flagsShift)) +#define DMA_IT_GLOB ((uint32_t)0x00000001) // channel global interput flag +#define DMA_IT_TCIF ((uint32_t)0x00000002) // channel full transport flag +#define DMA_IT_HTIF ((uint32_t)0x00000004) // channel half transport flag +#define DMA_IT_TEIF ((uint32_t)0x00000008) // channel transport error flag +#define DMA_IT_DMEIF ((uint32_t)0x00000004) // at32 has no direct mode transfer mode +#define DMA_HANDLER_CODE + +void dmaMuxEnable(dmaIdentifier_e identifier, uint32_t dmaMuxId); + +#define xDMA_Init(dmaResource, initStruct) dma_init((DMA_ARCH_TYPE *)(dmaResource), initStruct) +#define xDMA_DeInit(dmaResource) dma_reset((DMA_ARCH_TYPE *)(dmaResource)) +#define xDMA_Cmd(dmaResource, newState) dma_channel_enable((DMA_ARCH_TYPE *)(dmaResource), newState) +#define xDMA_ITConfig(dmaResource, flags, newState) dma_interrupt_enable((DMA_ARCH_TYPE *)(dmaResource), flags, newState) +#define xDMA_GetCurrDataCounter(dmaResource) dma_data_number_get((DMA_ARCH_TYPE *)(dmaResource)) +#define xDMA_SetCurrDataCounter(dmaResource, count) dma_data_number_set((DMA_ARCH_TYPE *)(dmaResource), count) +#define xDMA_GetFlagStatus(dmaResource, flags) dma_flag_get((DMA_ARCH_TYPE *)(dmaResource), flags) +#define xDMA_ClearFlag(dmaResource, flags) dma_flag_clear((DMA_ARCH_TYPE *)(dmaResource), flags) diff --git a/src/main/drivers/at32/persistent_at32bsp.c b/src/main/drivers/at32/persistent_at32bsp.c new file mode 100644 index 0000000000..be4c06c56e --- /dev/null +++ b/src/main/drivers/at32/persistent_at32bsp.c @@ -0,0 +1,66 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +/* + * An implementation of persistent data storage utilizing RTC backup data register. + * Retains values written across software resets and boot loader activities. + */ + +#include +#include "platform.h" + +#include "drivers/persistent.h" +#include "drivers/system.h" + +#define PERSISTENT_OBJECT_MAGIC_VALUE (('B' << 24)|('e' << 16)|('f' << 8)|('1' << 0)) + +uint32_t persistentObjectRead(persistentObjectId_e id) +{ + uint32_t value = ertc_bpr_data_read((ertc_dt_type)id); + return value; +} + +void persistentObjectWrite(persistentObjectId_e id, uint32_t value) +{ + ertc_bpr_data_write((ertc_dt_type)id, value); +} + +void persistentObjectRTCEnable(void) +{ + crm_periph_clock_enable(CRM_PWC_PERIPH_CLOCK, TRUE); + pwc_battery_powered_domain_access(TRUE); + ertc_write_protect_enable(); + ertc_write_protect_disable(); +} + +void persistentObjectInit(void) +{ + persistentObjectRTCEnable(); + uint32_t wasSoftReset; + + wasSoftReset = crm_flag_get(CRM_SW_RESET_FLAG); + + if (!wasSoftReset || (persistentObjectRead(PERSISTENT_OBJECT_MAGIC) != PERSISTENT_OBJECT_MAGIC_VALUE)) { + for (int i = 1; i < PERSISTENT_OBJECT_COUNT; i++) { + persistentObjectWrite(i, 0); + } + persistentObjectWrite(PERSISTENT_OBJECT_MAGIC, PERSISTENT_OBJECT_MAGIC_VALUE); + } +} diff --git a/src/main/drivers/at32/pwm_output_at32bsp.c b/src/main/drivers/at32/pwm_output_at32bsp.c new file mode 100644 index 0000000000..915cd953ad --- /dev/null +++ b/src/main/drivers/at32/pwm_output_at32bsp.c @@ -0,0 +1,293 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include +#include +#include +#include + +#include "platform.h" + +#ifdef USE_PWM_OUTPUT + +#include "drivers/io.h" +#include "drivers/motor.h" +#include "drivers/pwm_output.h" +#include "drivers/time.h" +#include "drivers/timer.h" + +#include "pg/motor.h" + +FAST_DATA_ZERO_INIT pwmOutputPort_t motors[MAX_SUPPORTED_MOTORS]; + +static void pwmOCConfig(tmr_type *tim, uint8_t channel, uint16_t value, uint8_t output) +{ + tmr_output_config_type tmr_OCInitStruct; + tmr_output_default_para_init(&tmr_OCInitStruct); + tmr_OCInitStruct.oc_mode= TMR_OUTPUT_CONTROL_PWM_MODE_A; + + if (output & TIMER_OUTPUT_N_CHANNEL) { + tmr_OCInitStruct.occ_output_state = TRUE; + tmr_OCInitStruct.occ_idle_state = FALSE; + tmr_OCInitStruct.occ_polarity = (output & TIMER_OUTPUT_INVERTED) ? TMR_OUTPUT_ACTIVE_LOW : TMR_OUTPUT_ACTIVE_HIGH; + } else { + tmr_OCInitStruct.oc_output_state = TRUE; + tmr_OCInitStruct.oc_idle_state = TRUE; + tmr_OCInitStruct.oc_polarity = (output & TIMER_OUTPUT_INVERTED) ? TMR_OUTPUT_ACTIVE_LOW : TMR_OUTPUT_ACTIVE_HIGH; + } + tmr_channel_value_set(tim, (channel-1)*2, value); + tmr_output_channel_config(tim,(channel-1)*2, &tmr_OCInitStruct); + tmr_output_channel_buffer_enable(tim, ((channel-1)*2),TRUE); +} + +void pwmOutConfig(timerChannel_t *channel, const timerHardware_t *timerHardware, uint32_t hz, uint16_t period, uint16_t value, uint8_t inversion) +{ + configTimeBase(timerHardware->tim, period, hz); + pwmOCConfig(timerHardware->tim, + timerHardware->channel, + value, + inversion ? timerHardware->output ^ TIMER_OUTPUT_INVERTED : timerHardware->output + ); + + + tmr_output_enable(timerHardware->tim, TRUE); + tmr_counter_enable(timerHardware->tim, TRUE); + + channel->ccr = timerChCCR(timerHardware); + + channel->tim = timerHardware->tim; + + *channel->ccr = 0; +} + +static FAST_DATA_ZERO_INIT motorDevice_t motorPwmDevice; + +static void pwmWriteUnused(uint8_t index, float value) +{ + UNUSED(index); + UNUSED(value); +} + +static void pwmWriteStandard(uint8_t index, float value) +{ + /* TODO: move value to be a number between 0-1 (i.e. percent throttle from mixer) */ + *motors[index].channel.ccr = lrintf((value * motors[index].pulseScale) + motors[index].pulseOffset); +} + +void pwmShutdownPulsesForAllMotors(void) +{ + for (int index = 0; index < motorPwmDevice.count; index++) { + // Set the compare register to 0, which stops the output pulsing if the timer overflows + if (motors[index].channel.ccr) { + *motors[index].channel.ccr = 0; + } + } +} + +void pwmDisableMotors(void) +{ + pwmShutdownPulsesForAllMotors(); +} + +static motorVTable_t motorPwmVTable; +bool pwmEnableMotors(void) +{ + /* check motors can be enabled */ + return (motorPwmVTable.write != &pwmWriteUnused); +} + +bool pwmIsMotorEnabled(uint8_t index) +{ + return motors[index].enabled; +} + +static void pwmCompleteOneshotMotorUpdate(void) +{ + for (int index = 0; index < motorPwmDevice.count; index++) { + if (motors[index].forceOverflow) { + timerForceOverflow(motors[index].channel.tim); + } + // Set the compare register to 0, which stops the output pulsing if the timer overflows before the main loop completes again. + // This compare register will be set to the output value on the next main loop. + *motors[index].channel.ccr = 0; + } +} + +static float pwmConvertFromExternal(uint16_t externalValue) +{ + return (float)externalValue; +} + +static uint16_t pwmConvertToExternal(float motorValue) +{ + return (uint16_t)motorValue; +} + +static motorVTable_t motorPwmVTable = { + .postInit = motorPostInitNull, + .enable = pwmEnableMotors, + .disable = pwmDisableMotors, + .isMotorEnabled = pwmIsMotorEnabled, + .shutdown = pwmShutdownPulsesForAllMotors, + .convertExternalToMotor = pwmConvertFromExternal, + .convertMotorToExternal = pwmConvertToExternal, +}; + +motorDevice_t *motorPwmDevInit(const motorDevConfig_t *motorConfig, uint16_t idlePulse, uint8_t motorCount, bool useUnsyncedPwm) +{ + motorPwmDevice.vTable = motorPwmVTable; + + float sMin = 0; + float sLen = 0; + switch (motorConfig->motorPwmProtocol) { + default: + case PWM_TYPE_ONESHOT125: + sMin = 125e-6f; + sLen = 125e-6f; + break; + case PWM_TYPE_ONESHOT42: + sMin = 42e-6f; + sLen = 42e-6f; + break; + case PWM_TYPE_MULTISHOT: + sMin = 5e-6f; + sLen = 20e-6f; + break; + case PWM_TYPE_BRUSHED: + sMin = 0; + useUnsyncedPwm = true; + idlePulse = 0; + break; + case PWM_TYPE_STANDARD: + sMin = 1e-3f; + sLen = 1e-3f; + useUnsyncedPwm = true; + idlePulse = 0; + break; + } + + motorPwmDevice.vTable.write = pwmWriteStandard; + motorPwmDevice.vTable.updateStart = motorUpdateStartNull; + motorPwmDevice.vTable.updateComplete = useUnsyncedPwm ? motorUpdateCompleteNull : pwmCompleteOneshotMotorUpdate; + + for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) { + const unsigned reorderedMotorIndex = motorConfig->motorOutputReordering[motorIndex]; + const ioTag_t tag = motorConfig->ioTags[reorderedMotorIndex]; + const timerHardware_t *timerHardware = timerAllocate(tag, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex)); + + if (timerHardware == NULL) { + /* not enough motors initialised for the mixer or a break in the motors */ + motorPwmDevice.vTable.write = &pwmWriteUnused; + motorPwmDevice.vTable.updateComplete = motorUpdateCompleteNull; + /* TODO: block arming and add reason system cannot arm */ + return NULL; + } + + motors[motorIndex].io = IOGetByTag(tag); + IOInit(motors[motorIndex].io, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex)); + +#if defined(STM32F1) + IOConfigGPIO(motors[motorIndex].io, IOCFG_AF_PP); + //FIXME:AT32F1 可以配置pin mux ,需要在io里面改一下 +#else + IOConfigGPIOAF(motors[motorIndex].io, IOCFG_AF_PP, timerHardware->alternateFunction); +#endif + + /* standard PWM outputs */ + // margin of safety is 4 periods when unsynced + const unsigned pwmRateHz = useUnsyncedPwm ? motorConfig->motorPwmRate : ceilf(1 / ((sMin + sLen) * 4)); + + const uint32_t clock = timerClock(timerHardware->tim); + /* used to find the desired timer frequency for max resolution */ + const unsigned prescaler = ((clock / pwmRateHz) + 0xffff) / 0x10000; /* rounding up */ + const uint32_t hz = clock / prescaler; + const unsigned period = useUnsyncedPwm ? hz / pwmRateHz : 0xffff; + + /* + if brushed then it is the entire length of the period. + TODO: this can be moved back to periodMin and periodLen + once mixer outputs a 0..1 float value. + */ + motors[motorIndex].pulseScale = ((motorConfig->motorPwmProtocol == PWM_TYPE_BRUSHED) ? period : (sLen * hz)) / 1000.0f; + motors[motorIndex].pulseOffset = (sMin * hz) - (motors[motorIndex].pulseScale * 1000); + + pwmOutConfig(&motors[motorIndex].channel, timerHardware, hz, period, idlePulse, motorConfig->motorPwmInversion); + + bool timerAlreadyUsed = false; + for (int i = 0; i < motorIndex; i++) { + if (motors[i].channel.tim == motors[motorIndex].channel.tim) { + timerAlreadyUsed = true; + break; + } + } + motors[motorIndex].forceOverflow = !timerAlreadyUsed; + motors[motorIndex].enabled = true; + } + + return &motorPwmDevice; +} + +pwmOutputPort_t *pwmGetMotors(void) +{ + return motors; +} + +#ifdef USE_SERVOS +static pwmOutputPort_t servos[MAX_SUPPORTED_SERVOS]; + +void pwmWriteServo(uint8_t index, float value) +{ + if (index < MAX_SUPPORTED_SERVOS && servos[index].channel.ccr) { + *servos[index].channel.ccr = lrintf(value); + } +} + +void servoDevInit(const servoDevConfig_t *servoConfig) +{ + for (uint8_t servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) { + const ioTag_t tag = servoConfig->ioTags[servoIndex]; + + if (!tag) { + break; + } + + servos[servoIndex].io = IOGetByTag(tag); + + IOInit(servos[servoIndex].io, OWNER_SERVO, RESOURCE_INDEX(servoIndex)); + + const timerHardware_t *timer = timerAllocate(tag, OWNER_SERVO, RESOURCE_INDEX(servoIndex)); + + if (timer == NULL) { + /* flag failure and disable ability to arm */ + break; + } + +#if defined(STM32F1) + IOConfigGPIO(servos[servoIndex].io, IOCFG_AF_PP); +#else + IOConfigGPIOAF(servos[servoIndex].io, IOCFG_AF_PP, timer->alternateFunction); +#endif + + pwmOutConfig(&servos[servoIndex].channel, timer, PWM_TIMER_1MHZ, PWM_TIMER_1MHZ / servoConfig->servoPwmRate, servoConfig->servoCenterPulse, 0); + servos[servoIndex].enabled = true; + } +} +#endif // USE_SERVOS +#endif // USE_PWM_OUTPUT diff --git a/src/main/drivers/at32/serial_uart_at32bsp.c b/src/main/drivers/at32/serial_uart_at32bsp.c new file mode 100644 index 0000000000..12caa8504a --- /dev/null +++ b/src/main/drivers/at32/serial_uart_at32bsp.c @@ -0,0 +1,283 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +/* + * Initialization part of serial_uart.c using at32 bsp driver + * + * Authors: + * emsr ports the code to at32f435/7 +*/ + +#include +#include + +#include "platform.h" + +#ifdef USE_UART + +#include "build/build_config.h" +#include "build/atomic.h" + +#include "common/utils.h" +#include "drivers/inverter.h" +#include "drivers/nvic.h" +#include "drivers/rcc.h" + +#include "drivers/dma.h" + +#include "drivers/serial.h" +#include "drivers/serial_uart.h" +#include "drivers/serial_uart_impl.h" + +static void usartConfigurePinInversion(uartPort_t *uartPort) { +#if !defined(USE_INVERTER) && !defined(STM32F303xC) + UNUSED(uartPort); +#else + bool inverted = uartPort->port.options & SERIAL_INVERTED; + +#ifdef USE_INVERTER + if (inverted) { + // Enable hardware inverter if available. + enableInverter(uartPort->USARTx, TRUE); + } +#endif +#endif +} + +static uartDevice_t *uartFindDevice(uartPort_t *uartPort) +{ + for (uint32_t i = 0; i < UARTDEV_COUNT_MAX; i++) { + uartDevice_t *candidate = uartDevmap[i]; + + if (&candidate->port == uartPort) { + return candidate; + } + } + return NULL; +} + +static void uartConfigurePinSwap(uartPort_t *uartPort) +{ + uartDevice_t *uartDevice = uartFindDevice(uartPort); + if (!uartDevice) { + return; + } + + if (uartDevice->pinSwap) { + usart_transmit_receive_pin_swap(uartDevice->port.USARTx, TRUE); + } +} + +void uartReconfigure(uartPort_t *uartPort) +{ + usart_enable(uartPort->USARTx, FALSE); + //init + usart_init(uartPort->USARTx, + uartPort->port.baudRate, + (uartPort->port.options & SERIAL_PARITY_EVEN)? USART_DATA_9BITS:USART_DATA_8BITS, + (uartPort->port.options & SERIAL_STOPBITS_2) ? USART_STOP_2_BIT : USART_STOP_1_BIT); + + //set parity + usart_parity_selection_config(uartPort->USARTx, + (uartPort->port.options & SERIAL_PARITY_EVEN) ? USART_PARITY_EVEN : USART_PARITY_NONE); + + //set hardware control + usart_hardware_flow_control_set(uartPort->USARTx, USART_HARDWARE_FLOW_NONE); + + //set mode rx or tx + if (uartPort->port.mode & MODE_RX) { + usart_receiver_enable(uartPort->USARTx, TRUE); + } + + if (uartPort->port.mode & MODE_TX) { + usart_transmitter_enable(uartPort->USARTx, TRUE); + } + + //config pin inverter + usartConfigurePinInversion(uartPort); + + //config pin swap + uartConfigurePinSwap(uartPort); + + if (uartPort->port.options & SERIAL_BIDIR) { + usart_single_line_halfduplex_select(uartPort->USARTx, TRUE); + } else { + usart_single_line_halfduplex_select(uartPort->USARTx, FALSE); + } + //enable usart + usart_enable(uartPort->USARTx, TRUE); + + // Receive DMA or IRQ + dma_init_type DMA_InitStructure; + if (uartPort->port.mode & MODE_RX) { + if (uartPort->rxDMAResource) { + + dma_default_para_init(&DMA_InitStructure); + DMA_InitStructure.loop_mode_enable=TRUE; + DMA_InitStructure.peripheral_base_addr=uartPort->rxDMAPeripheralBaseAddr; + DMA_InitStructure.priority = DMA_PRIORITY_MEDIUM; + DMA_InitStructure.peripheral_inc_enable =FALSE; + DMA_InitStructure.peripheral_data_width =DMA_PERIPHERAL_DATA_WIDTH_BYTE; + DMA_InitStructure.memory_inc_enable =TRUE; + DMA_InitStructure.memory_data_width = DMA_MEMORY_DATA_WIDTH_BYTE; + DMA_InitStructure.memory_base_addr=(uint32_t)uartPort->port.rxBuffer; + DMA_InitStructure.buffer_size = uartPort->port.rxBufferSize; + DMA_InitStructure.direction= DMA_DIR_PERIPHERAL_TO_MEMORY; + + xDMA_DeInit(uartPort->rxDMAResource); + xDMA_Init(uartPort->rxDMAResource, &DMA_InitStructure); + xDMA_Cmd(uartPort->rxDMAResource, TRUE); + usart_dma_receiver_enable(uartPort->USARTx,TRUE); + uartPort->rxDMAPos = xDMA_GetCurrDataCounter(uartPort->rxDMAResource); + } else { + usart_flag_clear(uartPort->USARTx, USART_RDBF_FLAG); + usart_interrupt_enable(uartPort->USARTx, USART_RDBF_INT, TRUE); + usart_interrupt_enable(uartPort->USARTx, USART_IDLE_INT, TRUE); + } + } + + // Transmit DMA or IRQ + if (uartPort->port.mode & MODE_TX) { + if (uartPort->txDMAResource) { + dma_default_para_init(&DMA_InitStructure); + DMA_InitStructure.loop_mode_enable=FALSE; + DMA_InitStructure.peripheral_base_addr=uartPort->txDMAPeripheralBaseAddr; + DMA_InitStructure.priority = DMA_PRIORITY_MEDIUM; + DMA_InitStructure.peripheral_inc_enable =FALSE; + DMA_InitStructure.peripheral_data_width =DMA_PERIPHERAL_DATA_WIDTH_BYTE; + DMA_InitStructure.memory_inc_enable =TRUE; + DMA_InitStructure.memory_data_width = DMA_MEMORY_DATA_WIDTH_BYTE; + DMA_InitStructure.memory_base_addr=(uint32_t)uartPort->port.txBuffer; + DMA_InitStructure.buffer_size = uartPort->port.txBufferSize; + DMA_InitStructure.direction= DMA_DIR_MEMORY_TO_PERIPHERAL; + + xDMA_DeInit(uartPort->txDMAResource); + xDMA_Init(uartPort->txDMAResource, &DMA_InitStructure); + xDMA_ITConfig(uartPort->txDMAResource, DMA_IT_TCIF, TRUE); + xDMA_SetCurrDataCounter(uartPort->txDMAResource, 0); + usart_dma_transmitter_enable(uartPort->USARTx, TRUE); + + } else { + usart_interrupt_enable(uartPort->USARTx, USART_TDBE_INT, TRUE); + } + } + + usart_enable(uartPort->USARTx,TRUE); +} + +#ifdef USE_DMA +void uartTryStartTxDMA(uartPort_t *s) +{ + // uartTryStartTxDMA must be protected, since it is called from + // uartWrite and handleUsartTxDma (an ISR). + + ATOMIC_BLOCK(NVIC_PRIO_SERIALUART_TXDMA) { + if (IS_DMA_ENABLED(s->txDMAResource)) { + // DMA is already in progress + return; + } + + // For F4, there are cases that NDTR is non-zero upon TC interrupt. + // We couldn't find out the root cause, so mask the case here. + if (xDMA_GetCurrDataCounter(s->txDMAResource)) { + // Possible premature TC case. + goto reenable; + } + + if (s->port.txBufferHead == s->port.txBufferTail) { + // No more data to transmit. + s->txDMAEmpty = true; + return; + } + + // Start a new transaction. + ((DMA_ARCH_TYPE*)s->txDMAResource) -> maddr =(uint32_t)&s->port.txBuffer[s->port.txBufferTail]; + + if (s->port.txBufferHead > s->port.txBufferTail) { + xDMA_SetCurrDataCounter(s->txDMAResource, s->port.txBufferHead - s->port.txBufferTail); + s->port.txBufferTail = s->port.txBufferHead; + } else { + xDMA_SetCurrDataCounter(s->txDMAResource, s->port.txBufferSize - s->port.txBufferTail); + s->port.txBufferTail = 0; + } + s->txDMAEmpty = false; + + reenable: + xDMA_Cmd(s->txDMAResource, TRUE); + } +} +#endif + + +static void handleUsartTxDma(uartPort_t *s) +{ + uartTryStartTxDMA(s); +} + +void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor) +{ + uartPort_t *s = &(((uartDevice_t*)(descriptor->userParam))->port); + if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) + { + DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF); + DMA_CLEAR_FLAG(descriptor, DMA_IT_HTIF); + handleUsartTxDma(s); + } + + if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TEIF)) + { + DMA_CLEAR_FLAG(descriptor, DMA_IT_TEIF); + } +} + +void uartIrqHandler(uartPort_t *s) +{ + if (!s->rxDMAResource && (usart_flag_get(s->USARTx, USART_RDBF_FLAG) == SET)) { + if (s->port.rxCallback) { + s->port.rxCallback(s->USARTx->dt, s->port.rxCallbackData); + } else { + s->port.rxBuffer[s->port.rxBufferHead] = s->USARTx->dt; + s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize; + } + } + + if (!s->txDMAResource && (usart_flag_get(s->USARTx, USART_TDBE_FLAG) == SET)) { + if (s->port.txBufferTail != s->port.txBufferHead) { + usart_data_transmit(s->USARTx, s->port.txBuffer[s->port.txBufferTail]); + s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize; + } else { + usart_interrupt_enable(s->USARTx, USART_TDBE_INT, FALSE); + } + } + + if (usart_flag_get(s->USARTx, USART_ROERR_FLAG) == SET) { + usart_flag_clear(s->USARTx, USART_ROERR_FLAG); + } + + if (usart_flag_get(s->USARTx, USART_IDLEF_FLAG) == SET) { + if (s->port.idleCallback) { + s->port.idleCallback(); + } + + (void) s->USARTx->sts; + (void) s->USARTx->dt; + } +} +#endif // USE_UART diff --git a/src/main/drivers/at32/serial_uart_at32f43x.c b/src/main/drivers/at32/serial_uart_at32f43x.c new file mode 100644 index 0000000000..fe1fb90c0e --- /dev/null +++ b/src/main/drivers/at32/serial_uart_at32f43x.c @@ -0,0 +1,331 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + * + * Author: jflyper + */ + +#include +#include + +#include "platform.h" + +#ifdef USE_UART + +#include "drivers/system.h" +#include "drivers/dma.h" +#include "drivers/io.h" +#include "drivers/nvic.h" +#include "drivers/rcc.h" + +#include "drivers/serial.h" +#include "drivers/serial_uart.h" +#include "drivers/serial_uart_impl.h" + +#ifndef UART1_TX_DMA_CHANNEL +#define UART1_TX_DMA_CHANNEL NULL +#endif +#ifndef UART1_RX_DMA_CHANNEL +#define UART1_RX_DMA_CHANNEL NULL +#endif +#ifndef UART2_TX_DMA_CHANNEL +#define UART2_TX_DMA_CHANNEL NULL +#endif +#ifndef UART2_RX_DMA_CHANNEL +#define UART2_RX_DMA_CHANNEL NULL +#endif +#ifndef UART3_TX_DMA_CHANNEL +#define UART3_TX_DMA_CHANNEL NULL +#endif +#ifndef UART3_RX_DMA_CHANNEL +#define UART3_RX_DMA_CHANNEL NULL +#endif +#ifndef UART4_TX_DMA_CHANNEL +#define UART4_TX_DMA_CHANNEL NULL +#endif +#ifndef UART4_RX_DMA_CHANNEL +#define UART4_RX_DMA_CHANNEL NULL +#endif +#ifndef UART5_TX_DMA_CHANNEL +#define UART5_TX_DMA_CHANNEL NULL +#endif +#ifndef UART5_RX_DMA_CHANNEL +#define UART5_RX_DMA_CHANNEL NULL +#endif +#ifndef UART8_TX_DMA_CHANNEL +#define UART8_TX_DMA_CHANNEL NULL +#endif +#ifndef UART8_RX_DMA_CHANNEL +#define UART8_RX_DMA_CHANNEL NULL +#endif + +const uartHardware_t uartHardware[UARTDEV_COUNT] = { +#ifdef USE_UART1 + { + .device = UARTDEV_1, + .reg = USART1, +#ifdef USE_DMA + .rxDMAMuxId = DMAMUX_DMAREQ_ID_USART1_RX, + .rxDMAResource = (dmaResource_t *)UART1_RX_DMA_CHANNEL, + .txDMAMuxId = DMAMUX_DMAREQ_ID_USART1_TX, + .txDMAResource = (dmaResource_t *)UART1_TX_DMA_CHANNEL, +#endif + .rxPins = { + { DEFIO_TAG_E(PA10), GPIO_MUX_7 }, + { DEFIO_TAG_E(PB7), GPIO_MUX_7 }, + { DEFIO_TAG_E(PB3), GPIO_MUX_7 }, + }, + .txPins = { + { DEFIO_TAG_E(PA9), GPIO_MUX_7 }, + { DEFIO_TAG_E(PA15), GPIO_MUX_7 }, + { DEFIO_TAG_E(PB6), GPIO_MUX_7 }, + }, + .rcc = RCC_APB2(USART1), + .irqn = USART1_IRQn, + .txPriority = NVIC_PRIO_SERIALUART1_TXDMA, + .rxPriority = NVIC_PRIO_SERIALUART1, + .txBuffer = uart1TxBuffer, + .rxBuffer = uart1RxBuffer, + .txBufferSize = sizeof(uart1TxBuffer), + .rxBufferSize = sizeof(uart1RxBuffer), + }, +#endif + +#ifdef USE_UART2 + { + .device = UARTDEV_2, + .reg = USART2, +#ifdef USE_DMA + .rxDMAMuxId = DMAMUX_DMAREQ_ID_USART2_RX, + .rxDMAResource = (dmaResource_t *)UART2_RX_DMA_CHANNEL, + .txDMAMuxId = DMAMUX_DMAREQ_ID_USART2_TX, + .txDMAResource = (dmaResource_t *)UART2_TX_DMA_CHANNEL, +#endif + .rxPins = { + { DEFIO_TAG_E(PA3), GPIO_MUX_7 }, + { DEFIO_TAG_E(PA15), GPIO_MUX_8 }, + { DEFIO_TAG_E(PB0), GPIO_MUX_6 }, + }, + .txPins = { + { DEFIO_TAG_E(PA2), GPIO_MUX_7 }, + { DEFIO_TAG_E(PA8), GPIO_MUX_8 }, + { DEFIO_TAG_E(PA14), GPIO_MUX_8 }, + }, + .rcc = RCC_APB1(USART2), + .irqn = USART2_IRQn, + .txPriority = NVIC_PRIO_SERIALUART2_TXDMA, + .rxPriority = NVIC_PRIO_SERIALUART2, + .txBuffer = uart2TxBuffer, + .rxBuffer = uart2RxBuffer, + .txBufferSize = sizeof(uart2TxBuffer), + .rxBufferSize = sizeof(uart2RxBuffer), + }, +#endif + +#ifdef USE_UART3 + { + .device = UARTDEV_3, + .reg = USART3, +#ifdef USE_DMA + .rxDMAMuxId = DMAMUX_DMAREQ_ID_USART3_RX, + .rxDMAResource = (dmaResource_t *)UART3_RX_DMA_CHANNEL, + .txDMAMuxId = DMAMUX_DMAREQ_ID_USART3_TX, + .txDMAResource = (dmaResource_t *)UART3_TX_DMA_CHANNEL, +#endif + .rxPins = { + { DEFIO_TAG_E(PB11), GPIO_MUX_7 }, + { DEFIO_TAG_E(PC5 ), GPIO_MUX_7 }, + { DEFIO_TAG_E(PC11), GPIO_MUX_7 }, + }, + .txPins = { + { DEFIO_TAG_E(PB10), GPIO_MUX_7 }, + { DEFIO_TAG_E(PC4 ), GPIO_MUX_7 }, + { DEFIO_TAG_E(PC10), GPIO_MUX_7 }, + }, + .rcc = RCC_APB1(USART3), + .irqn = USART3_IRQn, + .txPriority = NVIC_PRIO_SERIALUART3_TXDMA, + .rxPriority = NVIC_PRIO_SERIALUART3, + .txBuffer = uart3TxBuffer, + .rxBuffer = uart3RxBuffer, + .txBufferSize = sizeof(uart3TxBuffer), + .rxBufferSize = sizeof(uart3RxBuffer), + }, +#endif + +#ifdef USE_UART4 + { + .device = UARTDEV_4, + .reg = UART4, +#ifdef USE_DMA + .rxDMAMuxId = DMAMUX_DMAREQ_ID_UART4_RX, + .rxDMAResource = (dmaResource_t *)UART4_RX_DMA_CHANNEL, + .txDMAMuxId = DMAMUX_DMAREQ_ID_UART4_TX, + .txDMAResource = (dmaResource_t *)UART4_TX_DMA_CHANNEL, +#endif + .rxPins = { + { DEFIO_TAG_E(PA1), GPIO_MUX_8 }, + { DEFIO_TAG_E(PC11), GPIO_MUX_8 }, + }, + .txPins = { + { DEFIO_TAG_E(PA0), GPIO_MUX_8 }, + { DEFIO_TAG_E(PC10), GPIO_MUX_8 }, + }, + .rcc = RCC_APB1(UART4), + .irqn = UART4_IRQn, + .txPriority = NVIC_PRIO_SERIALUART4_TXDMA, + .rxPriority = NVIC_PRIO_SERIALUART4, + .txBuffer = uart4TxBuffer, + .rxBuffer = uart4RxBuffer, + .txBufferSize = sizeof(uart4TxBuffer), + .rxBufferSize = sizeof(uart4RxBuffer), + }, +#endif + +#ifdef USE_UART5 + { + .device = UARTDEV_5, + .reg = UART5, +#ifdef USE_DMA + .rxDMAMuxId = DMAMUX_DMAREQ_ID_UART5_RX, + .rxDMAResource = (dmaResource_t *)UART5_RX_DMA_CHANNEL, + .txDMAMuxId = DMAMUX_DMAREQ_ID_UART5_TX, + .txDMAResource = (dmaResource_t *)UART5_TX_DMA_CHANNEL, +#endif + .rxPins = { + { DEFIO_TAG_E(PB5), GPIO_MUX_8 }, + { DEFIO_TAG_E(PB8), GPIO_MUX_8 }, + { DEFIO_TAG_E(PD2), GPIO_MUX_8 }, + { DEFIO_TAG_E(PE11), GPIO_MUX_8 }, + }, + .txPins = { + { DEFIO_TAG_E(PB6), GPIO_MUX_8 }, + { DEFIO_TAG_E(PB9), GPIO_MUX_8 }, + { DEFIO_TAG_E(PC12), GPIO_MUX_8 }, + { DEFIO_TAG_E(PE10), GPIO_MUX_8 }, + }, + .rcc = RCC_APB1(UART5), + .irqn = UART5_IRQn, + .txPriority = NVIC_PRIO_SERIALUART5_TXDMA, + .rxPriority = NVIC_PRIO_SERIALUART5, + .txBuffer = uart5TxBuffer, + .rxBuffer = uart5RxBuffer, + .txBufferSize = sizeof(uart5TxBuffer), + .rxBufferSize = sizeof(uart5RxBuffer), + }, +#endif + + +#ifdef USE_UART8 + { + .device = UARTDEV_8, + .reg = UART8, //USE UART8 FOR PIN CONFIG +#ifdef USE_DMA + .rxDMAMuxId = DMAMUX_DMAREQ_ID_UART8_RX, + .rxDMAResource = (dmaResource_t *)UART8_RX_DMA_CHANNEL, + .txDMAMuxId = DMAMUX_DMAREQ_ID_UART8_TX, + .txDMAResource = (dmaResource_t *)UART8_TX_DMA_CHANNEL, +#endif + .rxPins = { + { DEFIO_TAG_E(PC3), GPIO_MUX_8 }, + { DEFIO_TAG_E(PC9), GPIO_MUX_7 }, + }, + .txPins = { + { DEFIO_TAG_E(PC2), GPIO_MUX_8 }, + { DEFIO_TAG_E(PC8), GPIO_MUX_7 }, + }, + .rcc = RCC_APB1(UART8), + .irqn = UART8_IRQn, + .txPriority = NVIC_PRIO_SERIALUART8_TXDMA, + .rxPriority = NVIC_PRIO_SERIALUART8, + .txBuffer = uart8TxBuffer, + .rxBuffer = uart8RxBuffer, + .txBufferSize = sizeof(uart8TxBuffer), + .rxBufferSize = sizeof(uart8RxBuffer), + }, +#endif + +//TODO: ADD UART 6\7\8 HERE! + +}; + +uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options) +{ + uartDevice_t *uartdev = uartDevmap[device]; + if (!uartdev) { + return NULL; + } + + uartPort_t *s = &(uartdev->port); + + s->port.vTable = uartVTable; + + s->port.baudRate = baudRate; + + const uartHardware_t *hardware = uartdev->hardware; + + s->USARTx = hardware->reg; + + s->port.rxBuffer = hardware->rxBuffer; + s->port.txBuffer = hardware->txBuffer; + s->port.rxBufferSize = hardware->rxBufferSize; + s->port.txBufferSize = hardware->txBufferSize; + +#ifdef USE_DMA + uartConfigureDma(uartdev); +#endif + + if (hardware->rcc) { + RCC_ClockCmd(hardware->rcc, ENABLE); + } + + IO_t txIO = IOGetByTag(uartdev->tx.pin); + IO_t rxIO = IOGetByTag(uartdev->rx.pin); + + if ((options & SERIAL_BIDIR) && txIO) { + //mode,speed,otype,pupd + ioConfig_t ioCfg = IO_CONFIG( + GPIO_MODE_MUX, + GPIO_DRIVE_STRENGTH_STRONGER, + ((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP) || (options & SERIAL_BIDIR_PP_PD)) ? GPIO_OUTPUT_PUSH_PULL : GPIO_OUTPUT_OPEN_DRAIN, + (options & SERIAL_INVERTED) ? GPIO_PULL_DOWN : GPIO_PULL_UP + ); + IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device)); + IOConfigGPIOAF(txIO, ioCfg, uartdev->tx.af); + } else { + if ((mode & MODE_TX) && txIO) { + IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device)); + IOConfigGPIOAF(txIO, IOCFG_AF_PP, uartdev->tx.af); + } + + if ((mode & MODE_RX) && rxIO) { + IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(device)); + IOConfigGPIOAF(rxIO, IOCFG_AF_PP, uartdev->rx.af); + } + } + +#ifdef USE_DMA + if (!s->rxDMAResource) +#endif + { + nvic_irq_enable(hardware->irqn,NVIC_PRIORITY_BASE(hardware->rxPriority), NVIC_PRIORITY_SUB(hardware->rxPriority)); + } + + return s; +} +#endif // USE_UART diff --git a/src/main/drivers/at32/system_at32f43x.c b/src/main/drivers/at32/system_at32f43x.c new file mode 100644 index 0000000000..330455fc1b --- /dev/null +++ b/src/main/drivers/at32/system_at32f43x.c @@ -0,0 +1,123 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include +#include + +#include "platform.h" + +#include "drivers/exti.h" +#include "drivers/nvic.h" +#include "drivers/system.h" +#include "drivers/persistent.h" +#include "at32f435_437_clock.h" + +void systemReset(void) +{ + __disable_irq(); + NVIC_SystemReset(); +} + +void systemResetToBootloader(bootloaderRequestType_e requestType) +{ + switch (requestType) { + case BOOTLOADER_REQUEST_ROM: + default: + persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_BOOTLOADER_REQUEST_ROM); + + break; + } + + __disable_irq(); + NVIC_SystemReset(); +} + +typedef void resetHandler_t(void); + +typedef struct isrVector_s { + __I uint32_t stackEnd; + resetHandler_t *resetHandler; +} isrVector_t; + +void checkForBootLoaderRequest(void) +{ + uint32_t bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON); + + if (bootloaderRequest != RESET_BOOTLOADER_REQUEST_ROM) { + return; + } + persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_NONE); + + extern isrVector_t system_isr_vector_table_base; + + __set_MSP(system_isr_vector_table_base.stackEnd); + system_isr_vector_table_base.resetHandler(); + while (1); +} + +void enableGPIOPowerUsageAndNoiseReductions(void) +{ + //enable all needed periph + crm_periph_clock_enable( + CRM_GPIOA_PERIPH_CLOCK | + CRM_GPIOB_PERIPH_CLOCK | + CRM_GPIOC_PERIPH_CLOCK | + CRM_GPIOD_PERIPH_CLOCK | + CRM_GPIOE_PERIPH_CLOCK | + CRM_DMA1_PERIPH_CLOCK | + CRM_DMA2_PERIPH_CLOCK | + 0,TRUE); +} + +bool isMPUSoftReset(void) +{ + if (cachedRccCsrValue & CRM_SW_RESET_FLAG) + return true; + else + return false; +} + +void systemInit(void) +{ + system_clock_config();//config system clock to 288mhz usb 48mhz + + // Configure NVIC preempt/priority groups + nvic_priority_group_config(NVIC_PRIORITY_GROUPING); + + // cache RCC->CSR value to use it in isMPUSoftReset() and others + cachedRccCsrValue = CRM->ctrlsts; + + // Although VTOR is already loaded with a possible vector table in RAM, + // removing the call to NVIC_SetVectorTable causes USB not to become active, + extern uint8_t isr_vector_table_base; + nvic_vector_table_set((uint32_t)&isr_vector_table_base, 0x0); + + crm_periph_clock_enable(CRM_OTGFS2_PERIPH_CLOCK|CRM_OTGFS1_PERIPH_CLOCK,FALSE); + + CRM->ctrlsts_bit.rstfc = TRUE; + + enableGPIOPowerUsageAndNoiseReductions(); + + // Init cycle counter + cycleCounterInit(); + + // SysTick + SysTick_Config(system_core_clock / 1000); +} diff --git a/src/main/drivers/at32/timer_at32bsp.c b/src/main/drivers/at32/timer_at32bsp.c new file mode 100644 index 0000000000..eb9583ae84 --- /dev/null +++ b/src/main/drivers/at32/timer_at32bsp.c @@ -0,0 +1,770 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include +#include +#include +#include + +#include "platform.h" + +#ifdef USE_TIMER + +#include "build/atomic.h" + +#include "common/utils.h" + +#include "drivers/nvic.h" + +#include "drivers/io.h" +#include "drivers/rcc.h" +#include "drivers/system.h" +#include "drivers/timer.h" +#include "drivers/timer_impl.h" + +#define TIM_N(n) (1 << (n)) + +/* + Groups that allow running different period (ex 50Hz servos + 400Hz throttle + etc): + TIM1 2 channels + TIM2 4 channels + TIM3 4 channels + TIM4 4 channels +*/ + +#define USED_TIMER_COUNT BITCOUNT(USED_TIMERS) +#define CC_CHANNELS_PER_TIMER 4 + +#define TIM_IT_CCx(ch) (TMR_C1_INT << ((ch)-1)) + +#define TIM_CH_TO_SELCHANNEL(ch) (( ch -1)*2) + +typedef struct timerConfig_s { + timerOvrHandlerRec_t *updateCallback; + + // per-channel + timerCCHandlerRec_t *edgeCallback[CC_CHANNELS_PER_TIMER]; + timerOvrHandlerRec_t *overflowCallback[CC_CHANNELS_PER_TIMER]; + + // state + timerOvrHandlerRec_t *overflowCallbackActive; // null-terminated linked list of active overflow callbacks + uint32_t forcedOverflowTimerValue; +} timerConfig_t; + +timerConfig_t timerConfig[USED_TIMER_COUNT]; + +typedef struct { + channelType_t type; +} timerChannelInfo_t; + +timerChannelInfo_t timerChannelInfo[TIMER_CHANNEL_COUNT]; + +typedef struct { + uint8_t priority; +} timerInfo_t; +timerInfo_t timerInfo[USED_TIMER_COUNT]; + +// return index of timer in timer table. Lowest timer has index 0 +#define TIMER_INDEX(i) BITCOUNT((TIM_N(i) - 1) & USED_TIMERS) + +static uint8_t lookupTimerIndex(const tmr_type *tim) +{ +#define _CASE_SHF 10 // amount we can safely shift timer address to the right. gcc will throw error if some timers overlap +#define _CASE_(tim, index) case ((unsigned)tim >> _CASE_SHF): return index; break +#define _CASE(i) _CASE_(TMR##i##_BASE, TIMER_INDEX(i)) + +// let gcc do the work, switch should be quite optimized + switch ((unsigned)tim >> _CASE_SHF) { +#if USED_TIMERS & TIM_N(1) + _CASE(1); +#endif +#if USED_TIMERS & TIM_N(2) + _CASE(2); +#endif +#if USED_TIMERS & TIM_N(3) + _CASE(3); +#endif +#if USED_TIMERS & TIM_N(4) + _CASE(4); +#endif +#if USED_TIMERS & TIM_N(5) + _CASE(5); +#endif +#if USED_TIMERS & TIM_N(6) + _CASE(6); +#endif +#if USED_TIMERS & TIM_N(7) + _CASE(7); +#endif +#if USED_TIMERS & TIM_N(8) + _CASE(8); +#endif +#if USED_TIMERS & TIM_N(9) + _CASE(9); +#endif +#if USED_TIMERS & TIM_N(10) + _CASE(10); +#endif +#if USED_TIMERS & TIM_N(11) + _CASE(11); +#endif +#if USED_TIMERS & TIM_N(12) + _CASE(12); +#endif +#if USED_TIMERS & TIM_N(13) + _CASE(13); +#endif +#if USED_TIMERS & TIM_N(14) + _CASE(14); +#endif +#if USED_TIMERS & TIM_N(15) + _CASE(15); +#endif +#if USED_TIMERS & TIM_N(16) + _CASE(16); +#endif +#if USED_TIMERS & TIM_N(17) + _CASE(17); +#endif + default: return ~1; // make sure final index is out of range + } +#undef _CASE +#undef _CASE_ +} + +tmr_type * const usedTimers[USED_TIMER_COUNT] = { +#define _DEF(i) TMR##i + +#if USED_TIMERS & TIM_N(1) + _DEF(1), +#endif +#if USED_TIMERS & TIM_N(2) + _DEF(2), +#endif +#if USED_TIMERS & TIM_N(3) + _DEF(3), +#endif +#if USED_TIMERS & TIM_N(4) + _DEF(4), +#endif +#if USED_TIMERS & TIM_N(5) + _DEF(5), +#endif +#if USED_TIMERS & TIM_N(6) + _DEF(6), +#endif +#if USED_TIMERS & TIM_N(7) + _DEF(7), +#endif +#if USED_TIMERS & TIM_N(8) + _DEF(8), +#endif +#if USED_TIMERS & TIM_N(9) + _DEF(9), +#endif +#if USED_TIMERS & TIM_N(10) + _DEF(10), +#endif +#if USED_TIMERS & TIM_N(11) + _DEF(11), +#endif +#if USED_TIMERS & TIM_N(12) + _DEF(12), +#endif +#if USED_TIMERS & TIM_N(13) + _DEF(13), +#endif +#if USED_TIMERS & TIM_N(14) + _DEF(14), +#endif +#if USED_TIMERS & TIM_N(15) + _DEF(15), +#endif +#if USED_TIMERS & TIM_N(16) + _DEF(16), +#endif +#if USED_TIMERS & TIM_N(17) + _DEF(17), +#endif +#if USED_TIMERS & TIM_N(20) + _DEF(20), +#endif +#undef _DEF +}; + +// Map timer index to timer number (Straight copy of usedTimers array) +const int8_t timerNumbers[USED_TIMER_COUNT] = { +#define _DEF(i) i + +#if USED_TIMERS & TIM_N(1) + _DEF(1), +#endif +#if USED_TIMERS & TIM_N(2) + _DEF(2), +#endif +#if USED_TIMERS & TIM_N(3) + _DEF(3), +#endif +#if USED_TIMERS & TIM_N(4) + _DEF(4), +#endif +#if USED_TIMERS & TIM_N(5) + _DEF(5), +#endif +#if USED_TIMERS & TIM_N(6) + _DEF(6), +#endif +#if USED_TIMERS & TIM_N(7) + _DEF(7), +#endif +#if USED_TIMERS & TIM_N(8) + _DEF(8), +#endif +#if USED_TIMERS & TIM_N(9) + _DEF(9), +#endif +#if USED_TIMERS & TIM_N(10) + _DEF(10), +#endif +#if USED_TIMERS & TIM_N(11) + _DEF(11), +#endif +#if USED_TIMERS & TIM_N(12) + _DEF(12), +#endif +#if USED_TIMERS & TIM_N(13) + _DEF(13), +#endif +#if USED_TIMERS & TIM_N(14) + _DEF(14), +#endif +#if USED_TIMERS & TIM_N(15) + _DEF(15), +#endif +#if USED_TIMERS & TIM_N(16) + _DEF(16), +#endif +#if USED_TIMERS & TIM_N(17) + _DEF(17), +#endif +#if USED_TIMERS & TIM_N(20) + _DEF(20), +#endif +#undef _DEF +}; + +int8_t timerGetNumberByIndex(uint8_t index) +{ + if (index < USED_TIMER_COUNT) { + return timerNumbers[index]; + } else { + return 0; + } +} + +int8_t timerGetTIMNumber(const tmr_type *tim) +{ + const uint8_t index = lookupTimerIndex(tim); + + return timerGetNumberByIndex(index); +} + +static inline uint8_t lookupChannelIndex(const uint16_t channel) +{ +// return channel >> 2; + return channel -1 ;//at32 use 1\2\3\4 as channel num +} + +uint8_t timerLookupChannelIndex(const uint16_t channel) +{ + return lookupChannelIndex(channel); +} + +rccPeriphTag_t timerRCC(tmr_type *tim) +{ + for (int i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) { + if (timerDefinitions[i].TIMx == tim) { + return timerDefinitions[i].rcc; + } + } + return 0; +} + +uint8_t timerInputIrq(tmr_type *tim) +{ + for (int i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) { + if (timerDefinitions[i].TIMx == tim) { + return timerDefinitions[i].inputIrq; + } + } + return 0; +} + +void timerNVICConfigure(uint8_t irq) +{ + nvic_irq_enable(irq,NVIC_PRIORITY_BASE(NVIC_PRIO_TIMER),NVIC_PRIORITY_SUB(NVIC_PRIO_TIMER)); +} + +void configTimeBase(tmr_type *tim, uint16_t period, uint32_t hz) +{ + //timer, period, perscaler + tmr_base_init(tim,(period - 1) & 0xFFFF,(timerClock(tim) / hz) - 1); + //TMR_CLOCK_DIV1 = 0X00 NO DIV + tmr_clock_source_div_set(tim,TMR_CLOCK_DIV1); + //COUNT UP + tmr_cnt_dir_set(tim,TMR_COUNT_UP); + +} + +// old interface for PWM inputs. It should be replaced +void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, uint32_t hz) +{ + configTimeBase(timerHardwarePtr->tim, period, hz); + tmr_counter_enable(timerHardwarePtr->tim, TRUE); + + uint8_t irq = timerInputIrq(timerHardwarePtr->tim); + timerNVICConfigure(irq); + switch (irq) { +#if defined(AT32F4) + case TMR1_CH_IRQn: + timerNVICConfigure(TMR1_OVF_TMR10_IRQn); + break; +#endif + } +} + +// allocate and configure timer channel. Timer priority is set to highest priority of its channels +void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriority, uint8_t irq) +{ + unsigned channel = timHw - TIMER_HARDWARE; + if (channel >= TIMER_CHANNEL_COUNT) { + return; + } + + timerChannelInfo[channel].type = type; + unsigned timer = lookupTimerIndex(timHw->tim); + if (timer >= USED_TIMER_COUNT) + return; + if (irqPriority < timerInfo[timer].priority) { + // it would be better to set priority in the end, but current startup sequence is not ready + configTimeBase(usedTimers[timer], 0, 1); + tmr_counter_enable(usedTimers[timer], TRUE); + + nvic_irq_enable(irq, NVIC_PRIORITY_BASE(irqPriority), NVIC_PRIORITY_SUB(irqPriority)); + + timerInfo[timer].priority = irqPriority; + } +} + +void timerChCCHandlerInit(timerCCHandlerRec_t *self, timerCCHandlerCallback *fn) +{ + self->fn = fn; +} + +void timerChOvrHandlerInit(timerOvrHandlerRec_t *self, timerOvrHandlerCallback *fn) +{ + self->fn = fn; + self->next = NULL; +} + +// update overflow callback list +// some synchronization mechanism is neccesary to avoid disturbing other channels (BASEPRI used now) +static void timerChConfig_UpdateOverflow(timerConfig_t *cfg, const tmr_type *tim) { + timerOvrHandlerRec_t **chain = &cfg->overflowCallbackActive; + ATOMIC_BLOCK(NVIC_PRIO_TIMER) { + + if (cfg->updateCallback) { + *chain = cfg->updateCallback; + chain = &cfg->updateCallback->next; + } + + for (int i = 0; i < CC_CHANNELS_PER_TIMER; i++) + if (cfg->overflowCallback[i]) { + *chain = cfg->overflowCallback[i]; + chain = &cfg->overflowCallback[i]->next; + } + *chain = NULL; + } + // enable or disable IRQ + tmr_interrupt_enable((tmr_type *)tim, TMR_OVF_INT, cfg->overflowCallbackActive ? TRUE : FALSE); +} + +// config edge and overflow callback for channel. Try to avoid per-channel overflowCallback, it is a bit expensive +void timerChConfigCallbacks(const timerHardware_t *timHw, timerCCHandlerRec_t *edgeCallback, timerOvrHandlerRec_t *overflowCallback) +{ + uint8_t timerIndex = lookupTimerIndex(timHw->tim); + if (timerIndex >= USED_TIMER_COUNT) { + return; + } + + uint8_t channelIndex = lookupChannelIndex(timHw->channel); + if (edgeCallback == NULL) { + // disable irq before changing callback to NULL + tmr_interrupt_enable(timHw->tim, TIM_IT_CCx(timHw->channel), FALSE); + } + + // setup callback info + timerConfig[timerIndex].edgeCallback[channelIndex] = edgeCallback; + timerConfig[timerIndex].overflowCallback[channelIndex] = overflowCallback; + // enable channel IRQ + if (edgeCallback) { + tmr_interrupt_enable(timHw->tim, TIM_IT_CCx(timHw->channel), TRUE); + } + + timerChConfig_UpdateOverflow(&timerConfig[timerIndex], timHw->tim); +} + +void timerConfigUpdateCallback(const tmr_type *tim, timerOvrHandlerRec_t *updateCallback) +{ + uint8_t timerIndex = lookupTimerIndex(tim); + if (timerIndex >= USED_TIMER_COUNT) { + return; + } + timerConfig[timerIndex].updateCallback = updateCallback; + timerChConfig_UpdateOverflow(&timerConfig[timerIndex], tim); +} + +// enable or disable IRQ +void timerChITConfig(const timerHardware_t *timHw, FunctionalState newState) +{ + tmr_interrupt_enable(timHw->tim, TIM_IT_CCx(timHw->channel), newState ? TRUE : FALSE); +} + +// clear Compare/Capture flag for channel +void timerChClearCCFlag(const timerHardware_t *timHw) +{ + tmr_flag_clear(timHw->tim, TIM_IT_CCx(timHw->channel)); +} + +// configure timer channel GPIO mode +void timerChConfigGPIO(const timerHardware_t* timHw, ioConfig_t mode) +{ + IOInit(IOGetByTag(timHw->tag), OWNER_TIMER, 0); + IOConfigGPIO(IOGetByTag(timHw->tag), mode); +} + +// calculate input filter constant +// TODO - we should probably setup DTS to higher value to allow reasonable input filtering +// - notice that prescaler[0] does use DTS for sampling - the sequence won't be monotonous anymore +static unsigned getFilter(unsigned ticks) +{ + static const unsigned ftab[16] = { + 1*1, // fDTS ! + 1*2, 1*4, 1*8, // fCK_INT + 2*6, 2*8, // fDTS/2 + 4*6, 4*8, + 8*6, 8*8, + 16*5, 16*6, 16*8, + 32*5, 32*6, 32*8 + }; + for (unsigned i = 1; i < ARRAYLEN(ftab); i++) + if (ftab[i] > ticks) + return i - 1; + return 0x0f; +} + +// Configure input capture +void timerChConfigIC(const timerHardware_t *timHw, bool polarityRising, unsigned inputFilterTicks) +{ + tmr_input_config_type tmr_icInitStructure; + tmr_icInitStructure.input_channel_select = TIM_CH_TO_SELCHANNEL(timHw->channel) ;// MAPS 1234 TO 0 2 4 6 + tmr_icInitStructure.input_polarity_select = polarityRising ?TMR_INPUT_RISING_EDGE:TMR_INPUT_FALLING_EDGE; + tmr_icInitStructure.input_mapped_select = TMR_CC_CHANNEL_MAPPED_DIRECT; + tmr_icInitStructure.input_filter_value = getFilter(inputFilterTicks); + + tmr_input_channel_init(timHw->tim,&tmr_icInitStructure,TMR_CHANNEL_INPUT_DIV_1); +} + +volatile timCCR_t* timerChCCR(const timerHardware_t *timHw) +{ + + if(timHw->channel ==1) + return (volatile timCCR_t*)(&timHw->tim->c1dt); + else if(timHw->channel ==2) + return (volatile timCCR_t*)(&timHw->tim->c2dt); + else if(timHw->channel ==3) + return (volatile timCCR_t*)(&timHw->tim->c3dt); + else if(timHw->channel ==4) + return (volatile timCCR_t*)(&timHw->tim->c4dt); + else + return (volatile timCCR_t*)((volatile char*)&timHw->tim->c1dt + (timHw->channel-1)*0x04); //for 32bit need to debug + +} + +static void timCCxHandler(tmr_type *tim, timerConfig_t *timerConfig) +{ + uint16_t capture; + unsigned tim_status; + tim_status = tim->ists & tim->iden; +#if 1 + while (tim_status) { + // flags will be cleared by reading CCR in dual capture, make sure we call handler correctly + // current order is highest bit first. Code should not rely on specific order (it will introduce race conditions anyway) + unsigned bit = __builtin_clz(tim_status); + unsigned mask = ~(0x80000000 >> bit); + tim->ists = mask; + tim_status &= mask; + switch (bit) { + case __builtin_clz(TMR_OVF_FLAG): { + + if (timerConfig->forcedOverflowTimerValue != 0) { + capture = timerConfig->forcedOverflowTimerValue - 1; + timerConfig->forcedOverflowTimerValue = 0; + } else { + capture = tim->pr; + } + + timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive; + while (cb) { + cb->fn(cb, capture); + cb = cb->next; + } + break; + } + case __builtin_clz(TMR_C1_FLAG): + timerConfig->edgeCallback[0]->fn(timerConfig->edgeCallback[0], tim->c1dt); + break; + case __builtin_clz(TMR_C2_FLAG): + timerConfig->edgeCallback[1]->fn(timerConfig->edgeCallback[1], tim->c2dt); + break; + case __builtin_clz(TMR_C3_FLAG): + timerConfig->edgeCallback[2]->fn(timerConfig->edgeCallback[2], tim->c3dt); + break; + case __builtin_clz(TMR_C4_FLAG): + timerConfig->edgeCallback[3]->fn(timerConfig->edgeCallback[3], tim->c4dt); + break; + } + } +#endif +} + +static inline void timUpdateHandler(tmr_type *tim, timerConfig_t *timerConfig) +{ + uint16_t capture; + unsigned tim_status; + tim_status = tim->ists & tim->iden; + while (tim_status) { + // flags will be cleared by reading CCR in dual capture, make sure we call handler correctly + // currrent order is highest bit first. Code should not rely on specific order (it will introduce race conditions anyway) + unsigned bit = __builtin_clz(tim_status); + unsigned mask = ~(0x80000000 >> bit); + tim->ists = mask; + tim_status &= mask; + switch (bit) { + case __builtin_clz(TMR_OVF_FLAG): { // tim_it_update= 0x0001 => TMR_OVF_FLAG + + if (timerConfig->forcedOverflowTimerValue != 0) { + capture = timerConfig->forcedOverflowTimerValue - 1; + timerConfig->forcedOverflowTimerValue = 0; + } else { + capture = tim->pr; + } + + timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive; + while (cb) { + cb->fn(cb, capture); + cb = cb->next; + } + break; + } + } + } +} + +// handler for shared interrupts when both timers need to check status bits +#define _TIM_IRQ_HANDLER2(name, i, j) \ + void name(void) \ + { \ + timCCxHandler(TMR ## i, &timerConfig[TIMER_INDEX(i)]); \ + timCCxHandler(TMR ## j, &timerConfig[TIMER_INDEX(j)]); \ + } struct dummy + +#define _TIM_IRQ_HANDLER(name, i) \ + void name(void) \ + { \ + timCCxHandler(TMR ## i, &timerConfig[TIMER_INDEX(i)]); \ + } struct dummy + +#define _TIM_IRQ_HANDLER_UPDATE_ONLY(name, i) \ + void name(void) \ + { \ + timUpdateHandler(TMR ## i, &timerConfig[TIMER_INDEX(i)]); \ + } struct dummy + +#if USED_TIMERS & TIM_N(1) +_TIM_IRQ_HANDLER(TMR1_CH_IRQHandler, 1); +#endif +#if USED_TIMERS & TIM_N(2) +_TIM_IRQ_HANDLER(TMR2_GLOBAL_IRQHandler, 2); +#endif +#if USED_TIMERS & TIM_N(3) +_TIM_IRQ_HANDLER(TMR3_GLOBAL_IRQHandler, 3); +#endif +#if USED_TIMERS & TIM_N(4) +_TIM_IRQ_HANDLER(TMR4_GLOBAL_IRQHandler, 4); +#endif +#if USED_TIMERS & TIM_N(5) +_TIM_IRQ_HANDLER(TMR5_GLOBAL_IRQHandler, 5); +#endif +#if USED_TIMERS & TIM_N(6) +_TIM_IRQ_HANDLER(TMR6_DAC_GLOBAL_IRQHandler, 6); +#endif + +#if USED_TIMERS & TIM_N(7) +_TIM_IRQ_HANDLER(TMR7_GLOBAL_IRQHandler, 7); +#endif + +#if USED_TIMERS & TIM_N(8) +_TIM_IRQ_HANDLER(TMR8_CH_IRQnHandler, 8); +#endif +#if USED_TIMERS & TIM_N(9) +_TIM_IRQ_HANDLER(TMR1_BRK_TMR9_IRQnHandler, 9); +#endif +//TODO: there may be a bug +#if USED_TIMERS & TIM_N(10) +_TIM_IRQ_HANDLER2(TMR1_OVF_TMR10_IRQnHandler, 1,10); +#endif +# if USED_TIMERS & TIM_N(11) +_TIM_IRQ_HANDLER(TMR1_TRG_HALL_TMR11_IRQnHandler, 11); +# endif +#if USED_TIMERS & TIM_N(12) +_TIM_IRQ_HANDLER(TMR8_BRK_TMR12_IRQnHandler, 12); +#endif +#if USED_TIMERS & TIM_N(13) +_TIM_IRQ_HANDLER(TMR8_OVF_TMR13_IRQnHandler, 13); +#endif +#if USED_TIMERS & TIM_N(14) +_TIM_IRQ_HANDLER(TMR8_TRG_HALL_TMR14_IRQnHandler, 14); +#endif +#if USED_TIMERS & TIM_N(20) +_TIM_IRQ_HANDLER(TMR20_CH_IRQnHandler, 20); +#endif + + +void timerInit(void) +{ + memset(timerConfig, 0, sizeof(timerConfig)); + +#if defined(PARTIAL_REMAP_TIM3) + GPIO_PinRemapConfig(GPIO_PartialRemap_TIM3, ENABLE); +#endif + + /* enable the timer peripherals */ + for (unsigned i = 0; i < TIMER_CHANNEL_COUNT; i++) { + RCC_ClockCmd(timerRCC(TIMER_HARDWARE[i].tim), ENABLE); + } + + // initialize timer channel structures + for (unsigned i = 0; i < TIMER_CHANNEL_COUNT; i++) { + timerChannelInfo[i].type = TYPE_FREE; + } + + for (unsigned i = 0; i < USED_TIMER_COUNT; i++) { + timerInfo[i].priority = ~0; + } +} + +// finish configuring timers after allocation phase +// start timers +void timerStart(void) +{ + +} + +/** + * Force an overflow for a given timer. + * Saves the current value of the counter in the relevant timerConfig's forcedOverflowTimerValue variable. + * @param tmr_type *tim The timer to overflow + * @return void + **/ +void timerForceOverflow(tmr_type *tim) +{ + uint8_t timerIndex = lookupTimerIndex((const tmr_type *)tim); + + ATOMIC_BLOCK(NVIC_PRIO_TIMER) { + // Save the current count so that PPM reading will work on the same timer that was forced to overflow + timerConfig[timerIndex].forcedOverflowTimerValue = tim->cval + 1; + + // Force an overflow by setting the UG bit + tim->swevt_bit.ovfswtr = 1; + } +} + +void timerOCInit(tmr_type *tim, uint8_t channel, tmr_output_config_type *init) +{ + tmr_output_channel_config(tim, TIM_CH_TO_SELCHANNEL(channel), init); +} + +void timerOCPreloadConfig(tmr_type *tim, uint8_t channel, uint16_t preload) +{ + tmr_output_channel_buffer_enable(tim, TIM_CH_TO_SELCHANNEL(channel), preload); +} + +//tmr_channel_value_get +volatile timCCR_t* timerCCR(tmr_type *tim, uint8_t channel) +{ + + if(channel ==1) + return (volatile timCCR_t*)(&tim->c1dt); + else if(channel ==2) + return (volatile timCCR_t*)(&tim->c2dt); + else if(channel ==3) + return (volatile timCCR_t*)(&tim->c3dt); + else if(channel ==4) + return (volatile timCCR_t*)(&tim->c4dt); + else + return (volatile timCCR_t*)((volatile char*)&tim->c1dt + (channel-1)*0x04); //for 32bit need to debug + +} + +uint16_t timerDmaSource(uint8_t channel) +{ + switch (channel) { + case 1: + return TMR_C1_DMA_REQUEST; + case 2: + return TMR_C2_DMA_REQUEST; + case 3: + return TMR_C3_DMA_REQUEST; + case 4: + return TMR_C4_DMA_REQUEST; + } + return 0; +} + +uint16_t timerGetPrescalerByDesiredMhz(tmr_type *tim, uint16_t mhz) +{ + return timerGetPrescalerByDesiredHertz(tim, MHZ_TO_HZ(mhz)); +} + +uint16_t timerGetPeriodByPrescaler(tmr_type *tim, uint16_t prescaler, uint32_t hz) +{ + return (uint16_t)((timerClock(tim) / (prescaler + 1)) / hz); +} + +uint16_t timerGetPrescalerByDesiredHertz(tmr_type *tim, uint32_t hz) +{ + // protection here for desired hertz > SystemCoreClock??? + if (hz > timerClock(tim)) { + return 0; + } + return (uint16_t)((timerClock(tim) + hz / 2 ) / hz) - 1; +} +#endif diff --git a/src/main/drivers/at32/timer_at32f43x.c b/src/main/drivers/at32/timer_at32f43x.c new file mode 100644 index 0000000000..828d00cf15 --- /dev/null +++ b/src/main/drivers/at32/timer_at32f43x.c @@ -0,0 +1,144 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include "platform.h" + +#ifdef USE_TIMER + +#include "common/utils.h" + +#include "drivers/dma.h" +#include "drivers/io.h" +#include "drivers/timer_def.h" + +#include "drivers/rcc.h" +#include "drivers/timer.h" + + +const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { + { .TIMx = TMR1, .rcc = RCC_APB2(TMR1), .inputIrq = TMR1_CH_IRQn}, + { .TIMx = TMR2, .rcc = RCC_APB1(TMR2), .inputIrq = TMR2_GLOBAL_IRQn}, + { .TIMx = TMR3, .rcc = RCC_APB1(TMR3), .inputIrq = TMR3_GLOBAL_IRQn}, + { .TIMx = TMR4, .rcc = RCC_APB1(TMR4), .inputIrq = TMR4_GLOBAL_IRQn}, + { .TIMx = TMR5, .rcc = RCC_APB1(TMR5), .inputIrq = TMR5_GLOBAL_IRQn}, + { .TIMx = TMR6, .rcc = RCC_APB1(TMR6), .inputIrq = TMR6_DAC_GLOBAL_IRQn}, + { .TIMx = TMR7, .rcc = RCC_APB1(TMR7), .inputIrq = TMR7_GLOBAL_IRQn}, + { .TIMx = TMR8, .rcc = RCC_APB2(TMR8), .inputIrq = TMR8_CH_IRQn}, + { .TIMx = TMR9, .rcc = RCC_APB2(TMR9), .inputIrq = TMR1_BRK_TMR9_IRQn}, + { .TIMx = TMR10, .rcc = RCC_APB2(TMR10), .inputIrq = TMR1_OVF_TMR10_IRQn}, + { .TIMx = TMR11, .rcc = RCC_APB2(TMR11), .inputIrq = TMR1_TRG_HALL_TMR11_IRQn}, + { .TIMx = TMR12, .rcc = RCC_APB1(TMR12), .inputIrq = TMR8_BRK_TMR12_IRQn}, + { .TIMx = TMR13, .rcc = RCC_APB1(TMR13), .inputIrq = TMR8_OVF_TMR13_IRQn}, + { .TIMx = TMR14, .rcc = RCC_APB1(TMR14), .inputIrq = TMR8_TRG_HALL_TMR14_IRQn}, + { .TIMx = TMR20, .rcc = RCC_APB2(TMR20), .inputIrq = TMR20_CH_IRQn}, + +}; + +#if defined(USE_TIMER_MGMT) +const timerHardware_t fullTimerHardware[FULL_TIMER_CHANNEL_COUNT] = { +// Port A + DEF_TIM(TMR2, CH1, PA0, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR2, CH2, PA1, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR2, CH3, PA2, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR2, CH4, PA3, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR2, CH1, PA5, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR2, CH1, PA15, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR5, CH1, PA0, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR5, CH2, PA1, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR5, CH3, PA2, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR5, CH4, PA3, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR3, CH1, PA6, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR3, CH2, PA7, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR8, CH1N, PA5, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR8, CH1N, PA7, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR1, CH1N, PA7, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR1, CH1, PA8, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR1, CH2, PA9, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR1, CH3, PA10, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR1, CH4, PA11, TIM_USE_ANY, 0, 0, 0), + + +// Port B ORDER BY MUX 1 2 3 + //MUX1 + DEF_TIM(TMR1, CH2N, PB0, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR1, CH3N, PB1, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR2, CH4, PB2, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR2, CH2, PB3, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR2, CH1, PB8, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR2, CH2, PB9, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR2, CH3, PB10, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR2, CH4, PB11, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR1, CH1N, PB13, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR1, CH2N, PB14, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR1, CH3N, PB15, TIM_USE_ANY, 0, 0, 0), +//MUX2 + DEF_TIM(TMR3, CH3, PB0, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR3, CH4, PB1, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR20, CH1, PB2, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR3, CH1, PB4, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR3, CH2, PB5, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR4, CH1, PB6, TIM_USE_ANY, 0, 13, 9),//FOR TARGET TEST only + DEF_TIM(TMR4, CH2, PB7, TIM_USE_ANY, 0, 12, 9), + DEF_TIM(TMR4, CH3, PB8, TIM_USE_ANY, 0, 11, 9), + DEF_TIM(TMR4, CH4, PB9, TIM_USE_ANY, 0, 10, 9), + DEF_TIM(TMR5, CH4, PB11, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR5, CH1, PB12, TIM_USE_ANY, 0, 0, 0), +//MUX3 + DEF_TIM(TMR8, CH2N, PB0, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR8, CH3N, PB1, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR8, CH2N, PB14, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR8, CH3N, PB15, TIM_USE_ANY, 0, 0, 0), + +// Port C ORDER BY MUX 1 2 3 + //MUX2 + DEF_TIM(TMR20, CH2, PC2, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR3, CH1, PC6, TIM_USE_ANY, 0, 0, 12),//for target test only + DEF_TIM(TMR3, CH2, PC7, TIM_USE_ANY, 0, 0, 12), + DEF_TIM(TMR3, CH3, PC8, TIM_USE_ANY, 0, 0, 12), + DEF_TIM(TMR3, CH4, PC9, TIM_USE_ANY, 0, 0, 12), + DEF_TIM(TMR5, CH2, PC10, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR5, CH3, PC11, TIM_USE_ANY, 0, 0, 0), +//MUX 3 + DEF_TIM(TMR8, CH1, PC6, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR8, CH2, PC7, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR8, CH3, PC8, TIM_USE_ANY, 0, 0, 0), + DEF_TIM(TMR8, CH4, PC9, TIM_USE_ANY, 0, 0, 0), + }; +#endif + +uint32_t timerClock(tmr_type *tim) +{ + /* + * RM0440 Rev.1 + * 6.2.13 Timer clock + * The timer clock frequencies are automatically defined by hardware. There are two cases: + * 1. If the APB prescaler equals 1, the timer clock frequencies are set to the same frequency as that of the APB domain. + * 2. Otherwise, they are set to twice (×2) the frequency of the APB domain. + */ + /* + * AN0085 雅特力AT32F435/7 MCU + * 定时器 TMRxClk源于 APB1/2 如果APB1/2 存在非1 分频时,TMRxClK 为APB1/2 时钟频率的2倍,与stm32 相同 + * 例如:system_core_clock =288mhz , apb1/2 =144mhz apb1_div=1 ,TMRxClk= apb1/2 *2 = 288Mhz + * + */ + UNUSED(tim); + return system_core_clock; +} +#endif diff --git a/src/main/drivers/at32/timer_def_at32.h b/src/main/drivers/at32/timer_def_at32.h new file mode 100644 index 0000000000..4ff5f58322 --- /dev/null +++ b/src/main/drivers/at32/timer_def_at32.h @@ -0,0 +1,406 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +#include "platform.h" +#include "common/utils.h" + +#define USED_TIMERS ( BIT(1) | BIT(2) | BIT(3) | BIT(4) | BIT(5) | BIT(8) | BIT(20)) +#define TIMUP_TIMERS ( BIT(1) | BIT(2) | BIT(3) | BIT(4) | BIT(5) | BIT(8) | BIT(9) | BIT(10) | BIT(11) | BIT(12) | BIT(13) |BIT(14) | BIT(20)) +#define FULL_TIMER_CHANNEL_COUNT 56 +#define HARDWARE_TIMER_DEFINITION_COUNT 15 + +// allow conditional definition of DMA related members +#if defined(USE_TIMER_DMA) +# define DEF_TIM_DMA_COND(...) __VA_ARGS__ +#else +# define DEF_TIM_DMA_COND(...) +#endif + +#if defined(USE_TIMER_MGMT) +#define TIMER_GET_IO_TAG(pin) DEFIO_TAG_E(pin) +#else +#define TIMER_GET_IO_TAG(pin) DEFIO_TAG(pin) +#endif + +// map to base channel (strip N from channel); works only when channel N exists +#define DEF_TIM_TCH2BTCH(timch) CONCAT(B, timch) +#define BTCH_TMR1_CH1N BTCH_TMR1_CH1 +#define BTCH_TMR1_CH2N BTCH_TMR1_CH2 +#define BTCH_TMR1_CH3N BTCH_TMR1_CH3 + +#define BTCH_TMR8_CH1N BTCH_TMR8_CH1 +#define BTCH_TMR8_CH2N BTCH_TMR8_CH2 +#define BTCH_TMR8_CH3N BTCH_TMR8_CH3 + +#define BTCH_TMR20_CH1N BTCH_TMR20_CH1 +#define BTCH_TMR20_CH2N BTCH_TMR20_CH2 +#define BTCH_TMR20_CH3N BTCH_TMR20_CH3 + +// channel table D(chan_n, n_type) +#define DEF_TIM_CH_GET(ch) CONCAT2(DEF_TIM_CH__, ch) +#define DEF_TIM_CH__CH_CH1 D(1, 0) +#define DEF_TIM_CH__CH_CH2 D(2, 0) +#define DEF_TIM_CH__CH_CH3 D(3, 0) +#define DEF_TIM_CH__CH_CH4 D(4, 0) +#define DEF_TIM_CH__CH_CH1N D(1, 1) +#define DEF_TIM_CH__CH_CH2N D(2, 1) +#define DEF_TIM_CH__CH_CH3N D(3, 1) + +// timer table D(tim_n) +#define DEF_TIM_TIM_GET(tim) CONCAT2(DEF_TIM_TIM__, tim) +#define DEF_TIM_TIM__TIM_TMR1 D(1) +#define DEF_TIM_TIM__TIM_TMR2 D(2) +#define DEF_TIM_TIM__TIM_TMR3 D(3) +#define DEF_TIM_TIM__TIM_TMR4 D(4) +#define DEF_TIM_TIM__TIM_TMR5 D(5) +#define DEF_TIM_TIM__TIM_TMR6 D(6) +#define DEF_TIM_TIM__TIM_TMR7 D(7) +#define DEF_TIM_TIM__TIM_TMR8 D(8) +#define DEF_TIM_TIM__TIM_TMR9 D(9) +#define DEF_TIM_TIM__TIM_TMR10 D(10) +#define DEF_TIM_TIM__TIM_TMR11 D(11) +#define DEF_TIM_TIM__TIM_TMR12 D(12) +#define DEF_TIM_TIM__TIM_TMR13 D(13) +#define DEF_TIM_TIM__TIM_TMR14 D(14) +#define DEF_TIM_TIM__TIM_TMR15 D(15) +#define DEF_TIM_TIM__TIM_TMR16 D(16) +#define DEF_TIM_TIM__TIM_TMR17 D(17) +#define DEF_TIM_TIM__TIM_TMR18 D(18) +#define DEF_TIM_TIM__TIM_TMR19 D(19) +#define DEF_TIM_TIM__TIM_TMR20 D(20) +#define DEF_TIM_TIM__TIM_TMR21 D(21) +#define DEF_TIM_TIM__TIM_TMR22 D(22) + +// Create accessor macro and call it with entry from table +// DMA_VARIANT_MISSING are used to satisfy variable arguments (-Wpedantic) and to get better error message (undefined symbol instead of preprocessor error) +#define DEF_TIM_DMA_GET(variant, timch) PP_CALL(CONCAT(DEF_TIM_DMA_GET_VARIANT__, variant), CONCAT(DEF_TIM_DMA__, DEF_TIM_TCH2BTCH(timch)), DMA_VARIANT_MISSING, DMA_VARIANT_MISSING, ERROR) + +#define DEF_TIM_DMA_GET_VARIANT__0(_0, ...) _0 +#define DEF_TIM_DMA_GET_VARIANT__1(_0, _1, ...) _1 +#define DEF_TIM_DMA_GET_VARIANT__2(_0, _1, _2, ...) _2 +#define DEF_TIM_DMA_GET_VARIANT__3(_0, _1, _2, _3, ...) _3 +#define DEF_TIM_DMA_GET_VARIANT__4(_0, _1, _2, _3, _4, ...) _4 +#define DEF_TIM_DMA_GET_VARIANT__5(_0, _1, _2, _3, _4, _5, ...) _5 +#define DEF_TIM_DMA_GET_VARIANT__6(_0, _1, _2, _3, _4, _5, _6, ...) _6 +#define DEF_TIM_DMA_GET_VARIANT__7(_0, _1, _2, _3, _4, _5, _6, _7, ...) _7 +#define DEF_TIM_DMA_GET_VARIANT__8(_0, _1, _2, _3, _4, _5, _6, _7, _8, ...) _8 +#define DEF_TIM_DMA_GET_VARIANT__9(_0, _1, _2, _3, _4, _5, _6, _7, _8, _9, ...) _9 +#define DEF_TIM_DMA_GET_VARIANT__10(_0, _1, _2, _3, _4, _5, _6, _7, _8, _9, _10, ...) _10 +#define DEF_TIM_DMA_GET_VARIANT__11(_0, _1, _2, _3, _4, _5, _6, _7, _8, _9, _10, _11, ...) _11 +#define DEF_TIM_DMA_GET_VARIANT__12(_0, _1, _2, _3, _4, _5, _6, _7, _8, _9, _10, _11, _12, ...) _12 +#define DEF_TIM_DMA_GET_VARIANT__13(_0, _1, _2, _3, _4, _5, _6, _7, _8, _9, _10, _11, _12, _13, ...) _13 +#define DEF_TIM_DMA_GET_VARIANT__14(_0, _1, _2, _3, _4, _5, _6, _7, _8, _9, _10, _11, _12, _13, _14, ...) _14 +#define DEF_TIM_DMA_GET_VARIANT__15(_0, _1, _2, _3, _4, _5, _6, _7, _8, _9, _10, _11, _12, _13, _14, _15, ...) _15 + +// symbolic names for DMA variants +#define DMA_VAR0 0 +#define DMA_VAR1 1 +#define DMA_VAR2 2 + +// get record from AF table +// Parameters in D(...) are target-specific +#define DEF_TIM_AF_GET(timch, pin) CONCAT4(DEF_TIM_AF__, pin, __, timch) + +//AF +#define DEF_TIM_AF(timch, pin) CONCAT(DEF_TIM_AF__, DEF_TIM_AF_GET(timch, pin)) +#define DEF_TIM_AF__D(af_n, tim_n) GPIO_MUX_ ## af_n /*GPIO_MUX_1 gpio_mux_sel_type */ + +// define output type (N-channel) +#define DEF_TIM_OUTPUT(ch) CONCAT(DEF_TIM_OUTPUT__, DEF_TIM_CH_GET(ch)) +#define DEF_TIM_OUTPUT__D(chan_n, n_channel) PP_IIF(n_channel, TIMER_OUTPUT_N_CHANNEL, TIMER_OUTPUT_NONE) + +/* + DEF_TIM(tim, chan, pin, flags, out,dmaopt,upopt) + @tim,chan tmr & channel + @pin output pin + @flags usage for timer + @out 0 for normal 1 for N_Channel + @dmaopt dma channel index used for timer channel data transmit + @upopt USE_DSHOT_DMAR timeup dma channel index +*/ +#define DEF_TIM(tim, chan, pin, flags, out, dmaopt, upopt) { \ + tim, \ + TIMER_GET_IO_TAG(pin), \ + DEF_TIM_CHANNEL(CH_ ## chan), \ + flags, \ + (DEF_TIM_OUTPUT(CH_ ## chan) | out), \ + DEF_TIM_AF(TCH_## tim ## _ ## chan, pin) \ + DEF_TIM_DMA_COND(/* add comma */ , \ + DEF_TIM_DMA_CHANNEL(dmaopt, TCH_## tim ## _ ## chan), \ + DEF_TIM_DMA_REQUEST(TCH_## tim ## _ ## chan) \ + ) \ + DEF_TIM_DMA_COND(/* add comma */ , \ + DEF_TIM_DMA_CHANNEL(upopt, TCH_## tim ## _UP), \ + DEF_TIM_DMA_REQUEST(TCH_## tim ## _UP), \ + DEF_TIM_DMA_HANDLER(upopt, TCH_## tim ## _UP) \ + ) \ +} +/**/ + +//Channel +#define DEF_TIM_CHANNEL(ch) CONCAT(DEF_TIM_CHANNEL__, DEF_TIM_CH_GET(ch)) +#define DEF_TIM_CHANNEL__D(chan_n, n_channel) chan_n + + +#define DEF_TIM_DMA_CHANNEL(variant, timch) \ + CONCAT(DEF_TIM_DMA_CHANNEL__, DEF_TIM_DMA_GET(variant, timch)) +#define DEF_TIM_DMA_CHANNEL__D(dma_n, channel_n) (dmaResource_t *)DMA ## dma_n ## _CHANNEL ## channel_n +#define DEF_TIM_DMA_CHANNEL__NONE NULL + +#define DEF_TIM_DMA_REQUEST(timch) \ + CONCAT(DEF_TIM_DMA_REQ__, DEF_TIM_TCH2BTCH(timch)) + +#define DEF_TIM_DMA_HANDLER(variant, timch) \ + CONCAT(DEF_TIM_DMA_HANDLER__, DEF_TIM_DMA_GET(variant, timch)) +#define DEF_TIM_DMA_HANDLER__D(dma_n, channel_n) DMA ## dma_n ## _CH ## channel_n ## _HANDLER +#define DEF_TIM_DMA_HANDLER__NONE 0 + + +/* DMA Channel Mappings */ +// D(DMAx, Stream) +// at32f43x has DMAMUX that allow arbitrary assignment of peripherals to streams. +#define DEF_TIM_DMA_FULL \ + D(1, 1), D(1, 2), D(1, 3), D(1, 4), D(1, 5), D(1, 6), D(1, 7), \ + D(2, 1), D(2, 2), D(2, 3), D(2, 4), D(2, 5), D(2, 6), D(2, 7) + +#define DEF_TIM_DMA__BTCH_TMR1_CH1 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR1_CH2 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR1_CH3 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR1_CH4 DEF_TIM_DMA_FULL + +#define DEF_TIM_DMA__BTCH_TMR2_CH1 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR2_CH2 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR2_CH3 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR2_CH4 DEF_TIM_DMA_FULL + +#define DEF_TIM_DMA__BTCH_TMR3_CH1 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR3_CH2 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR3_CH3 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR3_CH4 DEF_TIM_DMA_FULL + +#define DEF_TIM_DMA__BTCH_TMR4_CH1 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR4_CH2 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR4_CH3 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR4_CH4 DEF_TIM_DMA_FULL + +#define DEF_TIM_DMA__BTCH_TMR5_CH1 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR5_CH2 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR5_CH3 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR5_CH4 DEF_TIM_DMA_FULL + +#define DEF_TIM_DMA__BTCH_TMR8_CH1 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR8_CH2 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR8_CH3 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR8_CH4 DEF_TIM_DMA_FULL + +#define DEF_TIM_DMA__BTCH_TMR15_CH1 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR15_CH2 NONE + +#define DEF_TIM_DMA__BTCH_TMR16_CH1 DEF_TIM_DMA_FULL + +#define DEF_TIM_DMA__BTCH_TMR17_CH1 DEF_TIM_DMA_FULL + +#define DEF_TIM_DMA__BTCH_TMR20_CH1 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR20_CH2 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR20_CH3 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR20_CH4 DEF_TIM_DMA_FULL + +// TIM_UP table +#define DEF_TIM_DMA__BTCH_TMR1_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR2_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR3_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR4_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR5_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR6_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR7_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR8_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR15_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR16_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR17_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR20_UP DEF_TIM_DMA_FULL + +// TIMx_CHy request table + +#define DMA_REQUEST_NONE 255 + +#define DEF_TIM_DMA_REQ__BTCH_TMR1_CH1 DMAMUX_DMAREQ_ID_TMR1_CH1 +#define DEF_TIM_DMA_REQ__BTCH_TMR1_CH2 DMAMUX_DMAREQ_ID_TMR1_CH2 +#define DEF_TIM_DMA_REQ__BTCH_TMR1_CH3 DMAMUX_DMAREQ_ID_TMR1_CH3 +#define DEF_TIM_DMA_REQ__BTCH_TMR1_CH4 DMAMUX_DMAREQ_ID_TMR1_CH4 + +#define DEF_TIM_DMA_REQ__BTCH_TMR2_CH1 DMAMUX_DMAREQ_ID_TMR2_CH1 +#define DEF_TIM_DMA_REQ__BTCH_TMR2_CH2 DMAMUX_DMAREQ_ID_TMR2_CH2 +#define DEF_TIM_DMA_REQ__BTCH_TMR2_CH3 DMAMUX_DMAREQ_ID_TMR2_CH3 +#define DEF_TIM_DMA_REQ__BTCH_TMR2_CH4 DMAMUX_DMAREQ_ID_TMR2_CH4 + +#define DEF_TIM_DMA_REQ__BTCH_TMR3_CH1 DMAMUX_DMAREQ_ID_TMR3_CH1 +#define DEF_TIM_DMA_REQ__BTCH_TMR3_CH2 DMAMUX_DMAREQ_ID_TMR3_CH2 +#define DEF_TIM_DMA_REQ__BTCH_TMR3_CH3 DMAMUX_DMAREQ_ID_TMR3_CH3 +#define DEF_TIM_DMA_REQ__BTCH_TMR3_CH4 DMAMUX_DMAREQ_ID_TMR3_CH4 + +#define DEF_TIM_DMA_REQ__BTCH_TMR4_CH1 DMAMUX_DMAREQ_ID_TMR4_CH1 +#define DEF_TIM_DMA_REQ__BTCH_TMR4_CH2 DMAMUX_DMAREQ_ID_TMR4_CH2 +#define DEF_TIM_DMA_REQ__BTCH_TMR4_CH3 DMAMUX_DMAREQ_ID_TMR4_CH3 +#define DEF_TIM_DMA_REQ__BTCH_TMR4_CH4 DMAMUX_DMAREQ_ID_TMR4_CH4 + +#define DEF_TIM_DMA_REQ__BTCH_TMR5_CH1 DMAMUX_DMAREQ_ID_TMR5_CH1 +#define DEF_TIM_DMA_REQ__BTCH_TMR5_CH2 DMAMUX_DMAREQ_ID_TMR5_CH2 +#define DEF_TIM_DMA_REQ__BTCH_TMR5_CH3 DMAMUX_DMAREQ_ID_TMR5_CH3 +#define DEF_TIM_DMA_REQ__BTCH_TMR5_CH4 DMAMUX_DMAREQ_ID_TMR5_CH4 + +#define DEF_TIM_DMA_REQ__BTCH_TMR8_CH1 DMAMUX_DMAREQ_ID_TMR8_CH1 +#define DEF_TIM_DMA_REQ__BTCH_TMR8_CH2 DMAMUX_DMAREQ_ID_TMR8_CH2 +#define DEF_TIM_DMA_REQ__BTCH_TMR8_CH3 DMAMUX_DMAREQ_ID_TMR8_CH3 +#define DEF_TIM_DMA_REQ__BTCH_TMR8_CH4 DMAMUX_DMAREQ_ID_TMR8_CH4 + +#define DEF_TIM_DMA_REQ__BTCH_TMR20_CH1 DMAMUX_DMAREQ_ID_TMR20_CH1 +#define DEF_TIM_DMA_REQ__BTCH_TMR20_CH2 DMAMUX_DMAREQ_ID_TMR20_CH2 +#define DEF_TIM_DMA_REQ__BTCH_TMR20_CH3 DMAMUX_DMAREQ_ID_TMR20_CH3 +#define DEF_TIM_DMA_REQ__BTCH_TMR20_CH4 DMAMUX_DMAREQ_ID_TMR20_CH4 + +// TIM_UP request table +#define DEF_TIM_DMA_REQ__BTCH_TMR1_UP DMAMUX_DMAREQ_ID_TMR1_OVERFLOW +#define DEF_TIM_DMA_REQ__BTCH_TMR2_UP DMAMUX_DMAREQ_ID_TMR2_OVERFLOW +#define DEF_TIM_DMA_REQ__BTCH_TMR3_UP DMAMUX_DMAREQ_ID_TMR3_OVERFLOW +#define DEF_TIM_DMA_REQ__BTCH_TMR4_UP DMAMUX_DMAREQ_ID_TMR4_OVERFLOW +#define DEF_TIM_DMA_REQ__BTCH_TMR5_UP DMAMUX_DMAREQ_ID_TMR5_OVERFLOW +#define DEF_TIM_DMA_REQ__BTCH_TMR8_UP DMAMUX_DMAREQ_ID_TMR8_OVERFLOW +#define DEF_TIM_DMA_REQ__BTCH_TMR20_UP DMAMUX_DMAREQ_ID_TMR20_OVERFLOW + +// AF table for timer ,default is GPIO_MUX_1 should be check after debug + +//NONE d(mux_id, timerid) +#define DEF_TIM_AF__NONE__TCH_TMR1_CH1 D(1, 1) +#define DEF_TIM_AF__NONE__TCH_TMR1_CH2 D(1, 1) +#define DEF_TIM_AF__NONE__TCH_TMR1_CH3 D(1, 1) +#define DEF_TIM_AF__NONE__TCH_TMR1_CH4 D(1, 1) +#define DEF_TIM_AF__NONE__TCH_TMR8_CH1 D(1, 8) +#define DEF_TIM_AF__NONE__TCH_TMR8_CH2 D(1, 8) +#define DEF_TIM_AF__NONE__TCH_TMR8_CH3 D(1, 8) +#define DEF_TIM_AF__NONE__TCH_TMR8_CH4 D(1, 8) + +//PORTA MUX 1 +#define DEF_TIM_AF__PA0__TCH_TMR2_CH1 D(1, 2) +#define DEF_TIM_AF__PA1__TCH_TMR2_CH2 D(1, 2) +#define DEF_TIM_AF__PA2__TCH_TMR2_CH3 D(1, 2) +#define DEF_TIM_AF__PA3__TCH_TMR2_CH4 D(1, 2) +#define DEF_TIM_AF__PA5__TCH_TMR2_CH1 D(1, 2) +#define DEF_TIM_AF__PA7__TCH_TMR1_CH1N D(1, 1) +#define DEF_TIM_AF__PA8__TCH_TMR1_CH1 D(1, 1) +#define DEF_TIM_AF__PA9__TCH_TMR1_CH2 D(1, 1) +#define DEF_TIM_AF__PA10__TCH_TMR1_CH3 D(1, 1) +#define DEF_TIM_AF__PA11__TCH_TMR1_CH4 D(1, 1) +#define DEF_TIM_AF__PA15__TCH_TMR2_CH1 D(1, 2) +//PORTA MUX 2 +#define DEF_TIM_AF__PA0__TCH_TMR5_CH1 D(2, 5) +#define DEF_TIM_AF__PA1__TCH_TMR5_CH2 D(2, 5) +#define DEF_TIM_AF__PA2__TCH_TMR5_CH3 D(2, 5) +#define DEF_TIM_AF__PA3__TCH_TMR5_CH4 D(2, 5) +#define DEF_TIM_AF__PA6__TCH_TMR3_CH1 D(2, 3) +#define DEF_TIM_AF__PA7__TCH_TMR3_CH2 D(2, 3) + +//PORTA MUX 3 +//#define DEF_TIM_AF__PA0__TCH_TMR8_CH1N D(1, 15)//tmr8_ext +#define DEF_TIM_AF__PA2__TCH_TMR9_CH1 D(3, 9) +#define DEF_TIM_AF__PA3__TCH_TMR9_CH2 D(3, 9) +#define DEF_TIM_AF__PA5__TCH_TMR8_CH1N D(3, 8) +#define DEF_TIM_AF__PA7__TCH_TMR8_CH1N D(3, 8) + + +//PORTB MUX 1 +#define DEF_TIM_AF__PB0__TCH_TMR1_CH2N D(1, 1) +#define DEF_TIM_AF__PB1__TCH_TMR1_CH3N D(1, 1) +#define DEF_TIM_AF__PB2__TCH_TMR2_CH4 D(1, 2) +#define DEF_TIM_AF__PB3__TCH_TMR2_CH2 D(1, 2) +#define DEF_TIM_AF__PB8__TCH_TMR2_CH1 D(1, 2) +#define DEF_TIM_AF__PB9__TCH_TMR2_CH2 D(1, 2) +#define DEF_TIM_AF__PB10__TCH_TMR2_CH3 D(1, 2) +#define DEF_TIM_AF__PB11__TCH_TMR2_CH4 D(1, 2) +#define DEF_TIM_AF__PB13__TCH_TMR1_CH1N D(1, 1) +#define DEF_TIM_AF__PB14__TCH_TMR1_CH2N D(1, 1) +#define DEF_TIM_AF__PB15__TCH_TMR1_CH3N D(1, 1) +//PORTB MUX 2 +#define DEF_TIM_AF__PB0__TCH_TMR3_CH3 D(2, 3) +#define DEF_TIM_AF__PB1__TCH_TMR3_CH4 D(2, 3) +#define DEF_TIM_AF__PB2__TCH_TMR20_CH1 D(2, 20) +#define DEF_TIM_AF__PB4__TCH_TMR3_CH1 D(2, 3) +#define DEF_TIM_AF__PB5__TCH_TMR3_CH2 D(2, 3) +#define DEF_TIM_AF__PB6__TCH_TMR4_CH1 D(2, 4) +#define DEF_TIM_AF__PB7__TCH_TMR4_CH2 D(2, 4) +#define DEF_TIM_AF__PB8__TCH_TMR4_CH3 D(2, 4) +#define DEF_TIM_AF__PB9__TCH_TMR4_CH4 D(2, 4) +#define DEF_TIM_AF__PB11__TCH_TMR5_CH4 D(2, 5) +#define DEF_TIM_AF__PB12__TCH_TMR5_CH1 D(2, 5) + +//PORTB MUX 3 +#define DEF_TIM_AF__PB0__TCH_TMR8_CH2N D(3, 8) +#define DEF_TIM_AF__PB1__TCH_TMR8_CH3N D(3, 8) +#define DEF_TIM_AF__PB8__TCH_TMR10_CH1 D(3, 10) +#define DEF_TIM_AF__PB9__TCH_TMR11_CH1 D(3, 11) +#define DEF_TIM_AF__PB14__TCH_TMR8_CH2N D(3, 8) +#define DEF_TIM_AF__PB15__TCH_TMR8_CH3N D(3, 8) + +//PORTC MUX 2 +#define DEF_TIM_AF__PC2__TCH_TMR20_CH2 D(2, 20) +#define DEF_TIM_AF__PC6__TCH_TMR3_CH1 D(2, 3) +#define DEF_TIM_AF__PC7__TCH_TMR3_CH2 D(2, 3) +#define DEF_TIM_AF__PC8__TCH_TMR3_CH3 D(2, 3) +#define DEF_TIM_AF__PC9__TCH_TMR3_CH4 D(2, 3) +#define DEF_TIM_AF__PC10__TCH_TMR5_CH2 D(2, 5) +#define DEF_TIM_AF__PC11__TCH_TMR5_CH3 D(2, 5) + +//PORTC MUX 3 + +#define DEF_TIM_AF__PC4__TCH_TMR9_CH1 D(3, 9) +#define DEF_TIM_AF__PC5__TCH_TMR9_CH2 D(3, 9) +#define DEF_TIM_AF__PC6__TCH_TMR8_CH1 D(3, 8) +#define DEF_TIM_AF__PC7__TCH_TMR8_CH2 D(3, 8) +#define DEF_TIM_AF__PC8__TCH_TMR8_CH3 D(3, 8) +#define DEF_TIM_AF__PC9__TCH_TMR8_CH4 D(3, 8) +#define DEF_TIM_AF__PC12__TCH_TMR11_CH1N D(3, 11) + + +//PORTD MUX 2 +#define DEF_TIM_AF__PD12__TCH_TMR4_CH1 D(2, 4) +#define DEF_TIM_AF__PD13__TCH_TMR4_CH2 D(2, 4) +#define DEF_TIM_AF__PD14__TCH_TMR4_CH3 D(2, 4) +#define DEF_TIM_AF__PD15__TCH_TMR4_CH4 D(2, 4) + +//PORTE MUX 1 +#define DEF_TIM_AF__PE1__TCH_TMR1_CH2N D(1, 1) +#define DEF_TIM_AF__PE8__TCH_TMR1_CH1N D(1, 1) +#define DEF_TIM_AF__PE9__TCH_TMR1_CH1 D(1, 1) +#define DEF_TIM_AF__PE10__TCH_TMR1_CH2N D(1, 1) +#define DEF_TIM_AF__PE11__TCH_TMR1_CH2 D(1, 1) +#define DEF_TIM_AF__PE12__TCH_TMR1_CH3N D(1, 1) +#define DEF_TIM_AF__PE13__TCH_TMR1_CH3 D(1, 1) +#define DEF_TIM_AF__PE14__TCH_TMR1_CH4 D(1, 1) + +//PORTE MUX 2 +#define DEF_TIM_AF__PE3__TCH_TMR3_CH1 D(2, 3) +#define DEF_TIM_AF__PE4__TCH_TMR3_CH2 D(2, 3) +#define DEF_TIM_AF__PE5__TCH_TMR3_CH3 D(2, 3) +#define DEF_TIM_AF__PE6__TCH_TMR3_CH4 D(2, 3) + +//PORTE MUX 3 +#define DEF_TIM_AF__PE5__TCH_TMR9_CH1 D(2, 9) +#define DEF_TIM_AF__PE6__TCH_TMR9_CH2 D(2, 9) diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index 5de25e0c52..d43adda2fb 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -351,6 +351,12 @@ uint16_t spiCalculateDivider(uint32_t freq) uint32_t spiClk = SystemCoreClock / 2; #elif defined(STM32H7) uint32_t spiClk = 100000000; +#elif defined(AT32F4) + if(freq > 36000000){ + freq = 36000000; + } + + uint32_t spiClk = system_core_clock / 2; #else #error "Base SPI clock not defined for this architecture" #endif @@ -370,6 +376,13 @@ uint32_t spiCalculateClock(uint16_t spiClkDivisor) uint32_t spiClk = SystemCoreClock / 2; #elif defined(STM32H7) uint32_t spiClk = 100000000; +#elif defined (AT32F4) + uint32_t spiClk = system_core_clock / 2; + + if ((spiClk / spiClkDivisor) > 36000000){ + return 36000000; + } + #else #error "Base SPI clock not defined for this architecture" #endif @@ -408,6 +421,12 @@ FAST_IRQ_HANDLER static void spiIrqHandler(const extDevice_t *dev) nextSegment = (busSegment_t *)bus->curSegment + 1; if (nextSegment->len == 0) { +#if defined(USE_ATBSP_DRIVER) + if (!bus->curSegment->negateCS) { + // Negate Chip Select if not done so already + IOHi(dev->busType_u.spi.csnPin); + } +#endif // If a following transaction has been linked, start it if (nextSegment->u.link.dev) { const extDevice_t *nextDev = nextSegment->u.link.dev; @@ -588,11 +607,15 @@ void spiInitBusDMA(void) continue; } bus->dmaTx = dmaGetDescriptorByIdentifier(dmaTxIdentifier); +#if defined(STM32F4) || defined(STM32F7) || defined(STM32G4) || defined(STM32H7) bus->dmaTx->stream = DMA_DEVICE_INDEX(dmaTxIdentifier); bus->dmaTx->channel = dmaTxChannelSpec->channel; +#endif dmaEnable(dmaTxIdentifier); - +#if defined(USE_ATBSP_DRIVER) + dmaMuxEnable(dmaTxIdentifier,dmaTxChannelSpec->dmaMuxId); +#endif break; } } @@ -622,11 +645,15 @@ void spiInitBusDMA(void) continue; } bus->dmaRx = dmaGetDescriptorByIdentifier(dmaRxIdentifier); +#if defined(STM32F4) || defined(STM32F7) || defined(STM32G4) || defined(STM32H7) bus->dmaRx->stream = DMA_DEVICE_INDEX(dmaRxIdentifier); bus->dmaRx->channel = dmaRxChannelSpec->channel; +#endif dmaEnable(dmaRxIdentifier); - +#if defined(USE_ATBSP_DRIVER) + dmaMuxEnable(dmaRxIdentifier,dmaRxChannelSpec->dmaMuxId); +#endif break; } } diff --git a/src/main/drivers/bus_spi.h b/src/main/drivers/bus_spi.h index 019378b19b..85bb893507 100644 --- a/src/main/drivers/bus_spi.h +++ b/src/main/drivers/bus_spi.h @@ -39,6 +39,12 @@ #define SPI_IO_AF_SCK_CFG_LOW IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLDOWN) #define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP) #define SPI_IO_CS_CFG IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_NOPULL) +#elif defined(AT32F4) +#define SPI_IO_AF_CFG IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_NONE) +#define SPI_IO_AF_SCK_CFG_HIGH IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_UP) +#define SPI_IO_AF_SCK_CFG_LOW IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_DOWN) +#define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_UP) +#define SPI_IO_CS_CFG IO_CONFIG(GPIO_MODE_OUTPUT, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_NONE) #endif // De facto standard mode diff --git a/src/main/drivers/bus_spi_impl.h b/src/main/drivers/bus_spi_impl.h index 83aa446810..eadbb4cfbb 100644 --- a/src/main/drivers/bus_spi_impl.h +++ b/src/main/drivers/bus_spi_impl.h @@ -24,7 +24,7 @@ #if defined(STM32F4) || defined(STM32G4) #define MAX_SPI_PIN_SEL 2 -#elif defined(STM32F7) +#elif defined(STM32F7) || defined(AT32F4) #define MAX_SPI_PIN_SEL 4 #elif defined(STM32H7) #define MAX_SPI_PIN_SEL 5 @@ -36,7 +36,7 @@ typedef struct spiPinDef_s { ioTag_t pin; -#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) +#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) uint8_t af; #endif } spiPinDef_t; @@ -63,7 +63,7 @@ typedef struct SPIDevice_s { ioTag_t sck; ioTag_t miso; ioTag_t mosi; -#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) +#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) uint8_t sckAF; uint8_t misoAF; uint8_t mosiAF; diff --git a/src/main/drivers/bus_spi_pinconfig.c b/src/main/drivers/bus_spi_pinconfig.c index 9b4fd4a5f2..961980601f 100644 --- a/src/main/drivers/bus_spi_pinconfig.c +++ b/src/main/drivers/bus_spi_pinconfig.c @@ -342,6 +342,94 @@ const spiHardware_t spiHardware[] = { //.dmaIrqHandler = DMA1_ST7_HANDLER, }, #endif +#ifdef AT32F4 + { + .device = SPIDEV_1, + .reg = SPI1, + .sckPins = { + { DEFIO_TAG_E(PA5) ,GPIO_MUX_5}, + { DEFIO_TAG_E(PB3) ,GPIO_MUX_5}, + { DEFIO_TAG_E(PE13),GPIO_MUX_4}, + }, + .misoPins = { + { DEFIO_TAG_E(PA6) ,GPIO_MUX_5}, + { DEFIO_TAG_E(PB4) ,GPIO_MUX_5}, + { DEFIO_TAG_E(PE14),GPIO_MUX_4} + }, + .mosiPins = { + { DEFIO_TAG_E(PA7) ,GPIO_MUX_5}, + { DEFIO_TAG_E(PB5) ,GPIO_MUX_5}, + { DEFIO_TAG_E(PE15),GPIO_MUX_4}, + }, + .af= 0x00, + .rcc = RCC_APB2(SPI1), + }, + { + .device = SPIDEV_2, + .reg = SPI2, + .sckPins = { + { DEFIO_TAG_E(PB10), GPIO_MUX_5}, + { DEFIO_TAG_E(PB13) ,GPIO_MUX_5}, + { DEFIO_TAG_E(PC7), GPIO_MUX_5}, + { DEFIO_TAG_E(PD1), GPIO_MUX_6}, + + }, + .misoPins = { + { DEFIO_TAG_E(PA12), GPIO_MUX_5}, + { DEFIO_TAG_E(PB14), GPIO_MUX_5}, + { DEFIO_TAG_E(PC2), GPIO_MUX_5}, + { DEFIO_TAG_E(PD3), GPIO_MUX_6}, + }, + .mosiPins = { + { DEFIO_TAG_E(PB15), GPIO_MUX_5}, + { DEFIO_TAG_E(PC1), GPIO_MUX_7}, + { DEFIO_TAG_E(PC3), GPIO_MUX_5}, + { DEFIO_TAG_E(PD4), GPIO_MUX_6}, + }, + .af= 0x00, + .rcc = RCC_APB1(SPI2), + }, + { + .device = SPIDEV_3, + .reg = SPI3, + .sckPins = { + { DEFIO_TAG_E(PB3), GPIO_MUX_6}, + { DEFIO_TAG_E(PB12), GPIO_MUX_7}, + { DEFIO_TAG_E(PC10), GPIO_MUX_6}, + }, + .misoPins = { + { DEFIO_TAG_E(PB4), GPIO_MUX_6}, + { DEFIO_TAG_E(PC11), GPIO_MUX_6}, + }, + .mosiPins = { + { DEFIO_TAG_E(PB2), GPIO_MUX_7}, + { DEFIO_TAG_E(PB5), GPIO_MUX_6}, + { DEFIO_TAG_E(PC12), GPIO_MUX_6}, + { DEFIO_TAG_E(PD0), GPIO_MUX_6}, + }, + .af= 0x00, + .rcc = RCC_APB1(SPI3), + }, + { + .device = SPIDEV_4, + .reg = SPI4, + .sckPins = { + { DEFIO_TAG_E(PB7), GPIO_MUX_6}, + { DEFIO_TAG_E(PB13), GPIO_MUX_6}, + }, + .misoPins = { + { DEFIO_TAG_E(PA11), GPIO_MUX_6}, + { DEFIO_TAG_E(PB8) , GPIO_MUX_6}, + { DEFIO_TAG_E(PD0) , GPIO_MUX_5}, + }, + .mosiPins = { + { DEFIO_TAG_E(PA1), GPIO_MUX_5}, + { DEFIO_TAG_E(PB9), GPIO_MUX_6}, + }, + .af= 0x00, + .rcc = RCC_APB2(SPI4), + }, +#endif }; void spiPinConfigure(const spiPinConfig_t *pConfig) @@ -359,19 +447,19 @@ void spiPinConfigure(const spiPinConfig_t *pConfig) for (int pindex = 0 ; pindex < MAX_SPI_PIN_SEL ; pindex++) { if (pConfig[device].ioTagSck == hw->sckPins[pindex].pin) { pDev->sck = hw->sckPins[pindex].pin; -#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) +#if defined(USE_PIN_AF) pDev->sckAF = hw->sckPins[pindex].af; #endif } if (pConfig[device].ioTagMiso == hw->misoPins[pindex].pin) { pDev->miso = hw->misoPins[pindex].pin; -#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) +#if defined(USE_PIN_AF) pDev->misoAF = hw->misoPins[pindex].af; #endif } if (pConfig[device].ioTagMosi == hw->mosiPins[pindex].pin) { pDev->mosi = hw->mosiPins[pindex].pin; -#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) +#if defined(USE_PIN_AF) pDev->mosiAF = hw->mosiPins[pindex].af; #endif } @@ -379,7 +467,7 @@ void spiPinConfigure(const spiPinConfig_t *pConfig) if (pDev->sck && pDev->miso && pDev->mosi) { pDev->dev = hw->reg; -#if !(defined(STM32F7) || defined(STM32H7) || defined(STM32G4)) +#if !defined(USE_PIN_AF) pDev->af = hw->af; #endif pDev->rcc = hw->rcc; diff --git a/src/main/drivers/dma.h b/src/main/drivers/dma.h index 6d1a611954..85febf3c5a 100644 --- a/src/main/drivers/dma.h +++ b/src/main/drivers/dma.h @@ -22,6 +22,10 @@ #include "drivers/resource.h" +#if defined(USE_ATBSP_DRIVER) +#include "drivers/at32/dma_atbsp.h" +#endif + #define CACHE_LINE_SIZE 32 #define CACHE_LINE_MASK (CACHE_LINE_SIZE - 1) @@ -60,17 +64,16 @@ typedef struct dmaChannelDescriptor_s { resourceOwner_t owner; uint8_t resourceIndex; uint32_t completeFlag; -} dmaChannelDescriptor_t; - -#if defined(STM32F7) -//#define HAL_CLEANINVALIDATECACHE(addr, size) (SCB_CleanInvalidateDCache_by_Addr((uint32_t*)((uint32_t)addr & ~0x1f), ((uint32_t)(addr + size + 0x1f) & ~0x1f) - ((uint32_t)addr & ~0x1f))) -//#define HAL_CLEANCACHE(addr, size) (SCB_CleanDCache_by_Addr((uint32_t*)((uint32_t)addr & ~0x1f), ((uint32_t)(addr + size + 0x1f) & ~0x1f) - ((uint32_t)addr & ~0x1f))) - +#if defined(USE_ATBSP_DRIVER) + dmamux_channel_type *dmamux; #endif +} dmaChannelDescriptor_t; #define DMA_IDENTIFIER_TO_INDEX(x) ((x) - 1) -#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) +#if defined(USE_ATBSP_DRIVER) + +#elif defined(STM32F4) || defined(STM32F7) || defined(STM32H7) typedef enum { DMA_NONE = 0, @@ -128,6 +131,8 @@ typedef enum { #define DMA_IT_DMEIF ((uint32_t)0x00000004) #define DMA_IT_FEIF ((uint32_t)0x00000001) +void dmaMuxEnable(dmaIdentifier_e identifier, uint32_t dmaMuxId); + #else #if defined(STM32G4) @@ -207,7 +212,6 @@ typedef enum { #define DMA_IT_TCIF ((uint32_t)0x00000002) #define DMA_IT_HTIF ((uint32_t)0x00000004) #define DMA_IT_TEIF ((uint32_t)0x00000008) - #endif // Macros to avoid direct register and register bit access @@ -239,6 +243,9 @@ typedef enum { #define IS_DMA_ENABLED(reg) (((DMA_ARCH_TYPE *)(reg))->CCR & DMA_CCR_EN) // Missing __HAL_DMA_SET_COUNTER in FW library V1.0.0 #define __HAL_DMA_SET_COUNTER(__HANDLE__, __COUNTER__) ((__HANDLE__)->Instance->CNDTR = (uint16_t)(__COUNTER__)) +#elif defined(AT32F4) +#define DMA_CCR_EN 1 +#define IS_DMA_ENABLED(reg) (((DMA_ARCH_TYPE *)(reg))->ctrl_bit.chen & DMA_CCR_EN) #else #define IS_DMA_ENABLED(reg) (((DMA_ARCH_TYPE *)(reg))->CCR & DMA_CCR_EN) #define DMAx_SetMemoryAddress(reg, address) ((DMA_ARCH_TYPE *)(reg))->CMAR = (uint32_t)&s->port.txBuffer[s->port.txBufferTail] @@ -257,7 +264,7 @@ uint32_t dmaGetChannel(const uint8_t channel); // Wrapper macros to cast dmaResource_t back into DMA_ARCH_TYPE // -#ifdef USE_HAL_DRIVER +#if defined(USE_HAL_DRIVER) // We actually need these LL case only @@ -269,6 +276,8 @@ uint32_t dmaGetChannel(const uint8_t channel); #define xLL_EX_DMA_SetDataLength(dmaResource, length) LL_EX_DMA_SetDataLength((DMA_ARCH_TYPE *)(dmaResource), length) #define xLL_EX_DMA_EnableIT_TC(dmaResource) LL_EX_DMA_EnableIT_TC((DMA_ARCH_TYPE *)(dmaResource)) +#elif defined(USE_ATBSP_DRIVER) + #else #define xDMA_Init(dmaResource, initStruct) DMA_Init((DMA_ARCH_TYPE *)(dmaResource), initStruct) diff --git a/src/main/drivers/dma_reqmap.c b/src/main/drivers/dma_reqmap.c index 41f62a7a53..e66fbf5b98 100644 --- a/src/main/drivers/dma_reqmap.c +++ b/src/main/drivers/dma_reqmap.c @@ -37,7 +37,7 @@ typedef struct dmaPeripheralMapping_s { dmaPeripheral_e device; uint8_t index; -#if defined(STM32H7) || defined(STM32G4) +#if defined(STM32H7) || defined(STM32G4) || defined(AT32F4) uint8_t dmaRequest; #else dmaChannelSpec_t channelSpec[MAX_PERIPHERAL_DMA_OPTIONS]; @@ -47,13 +47,161 @@ typedef struct dmaPeripheralMapping_s { typedef struct dmaTimerMapping_s { TIM_TypeDef *tim; uint8_t channel; -#if defined(STM32H7) || defined(STM32G4) +#if defined(STM32H7) || defined(STM32G4) || defined(AT32F4) uint8_t dmaRequest; #else dmaChannelSpec_t channelSpec[MAX_TIMER_DMA_OPTIONS]; #endif } dmaTimerMapping_t; +#if defined(AT32F43x) + +#define REQMAP_SGL(periph) { DMA_PERIPH_ ## periph, 0, DMA_REQUEST_ ## periph } +#define REQMAP(periph, device) { DMA_PERIPH_ ## periph, periph ## DEV_ ## device, DMA_REQUEST_ ## periph ## device } +#define REQMAP_DIR(periph, device, dir) { DMA_PERIPH_ ## periph ## _ ## dir, periph ## DEV_ ## device, DMA_REQUEST_ ## periph ## device ## _ ## dir } +#define REQMAP_TIMUP(periph, timno) { DMA_PERIPH_TIMUP, timno - 1, DMAMUX_DMAREQ_ID_ ## TMR ## timno ## _OVERFLOW } + +#define DMA_REQUEST_UART1_RX DMAMUX_DMAREQ_ID_USART1_RX +#define DMA_REQUEST_UART1_TX DMAMUX_DMAREQ_ID_USART1_TX +#define DMA_REQUEST_UART2_RX DMAMUX_DMAREQ_ID_USART2_RX +#define DMA_REQUEST_UART2_TX DMAMUX_DMAREQ_ID_USART2_TX +#define DMA_REQUEST_UART3_RX DMAMUX_DMAREQ_ID_USART3_RX +#define DMA_REQUEST_UART3_TX DMAMUX_DMAREQ_ID_USART3_TX +#define DMA_REQUEST_UART4_RX DMAMUX_DMAREQ_ID_UART4_RX +#define DMA_REQUEST_UART4_TX DMAMUX_DMAREQ_ID_UART4_TX +#define DMA_REQUEST_UART5_RX DMAMUX_DMAREQ_ID_UART5_RX +#define DMA_REQUEST_UART5_TX DMAMUX_DMAREQ_ID_UART5_TX + +#define DMA_REQUEST_UART6_RX DMAMUX_DMAREQ_ID_USART6_RX +#define DMA_REQUEST_UART6_TX DMAMUX_DMAREQ_ID_USART6_TX + +// Resolve our preference for MOSI/MISO rather than TX/RX +#define DMA_REQUEST_SPI1_MOSI DMAMUX_DMAREQ_ID_SPI1_TX +#define DMA_REQUEST_SPI1_MISO DMAMUX_DMAREQ_ID_SPI1_RX +#define DMA_REQUEST_SPI2_MOSI DMAMUX_DMAREQ_ID_SPI2_TX +#define DMA_REQUEST_SPI2_MISO DMAMUX_DMAREQ_ID_SPI2_RX +#define DMA_REQUEST_SPI3_MOSI DMAMUX_DMAREQ_ID_SPI3_TX +#define DMA_REQUEST_SPI3_MISO DMAMUX_DMAREQ_ID_SPI3_RX +#define DMA_REQUEST_SPI4_MOSI DMAMUX_DMAREQ_ID_SPI4_TX +#define DMA_REQUEST_SPI4_MISO DMAMUX_DMAREQ_ID_SPI4_RX + +#define DMA_REQUEST_ADC1 DMAMUX_DMAREQ_ID_ADC1 +#define DMA_REQUEST_ADC2 DMAMUX_DMAREQ_ID_ADC2 +#define DMA_REQUEST_ADC3 DMAMUX_DMAREQ_ID_ADC3 + +static const dmaPeripheralMapping_t dmaPeripheralMapping[] = { +#ifdef USE_SPI + REQMAP_DIR(SPI, 1, MOSI), + REQMAP_DIR(SPI, 1, MISO), + REQMAP_DIR(SPI, 2, MOSI), + REQMAP_DIR(SPI, 2, MISO), + REQMAP_DIR(SPI, 3, MOSI), + REQMAP_DIR(SPI, 3, MISO), + REQMAP_DIR(SPI, 4, MOSI), + REQMAP_DIR(SPI, 4, MISO), +#endif // USE_SPI + +#ifdef USE_ADC + REQMAP(ADC, 1), + REQMAP(ADC, 2), + REQMAP(ADC, 3), +#endif + +#ifdef USE_UART + REQMAP_DIR(UART, 1, TX), + REQMAP_DIR(UART, 1, RX), + REQMAP_DIR(UART, 2, TX), + REQMAP_DIR(UART, 2, RX), + REQMAP_DIR(UART, 3, TX), + REQMAP_DIR(UART, 3, RX), + REQMAP_DIR(UART, 4, TX), + REQMAP_DIR(UART, 4, RX), + REQMAP_DIR(UART, 5, TX), + REQMAP_DIR(UART, 5, RX), + REQMAP_DIR(UART, 6, TX), + REQMAP_DIR(UART, 6, RX), +#endif + +#ifdef USE_TIMER + REQMAP_TIMUP(TIMUP, 1), + REQMAP_TIMUP(TIMUP, 2), + REQMAP_TIMUP(TIMUP, 3), + REQMAP_TIMUP(TIMUP, 4), + REQMAP_TIMUP(TIMUP, 5), + REQMAP_TIMUP(TIMUP, 6), + REQMAP_TIMUP(TIMUP, 7), + REQMAP_TIMUP(TIMUP, 8), + REQMAP_TIMUP(TIMUP, 20), +#endif +}; + +#undef REQMAP_TIMUP +#undef REQMAP +#undef REQMAP_SGL +#undef REQMAP_DIR + +#define TC(chan) DEF_TIM_CHANNEL(CH_ ## chan) //Tc 还不能映射 + +#define REQMAP_TIM(tim, chan) { tim, TC(chan), DMAMUX_DMAREQ_ID_ ## tim ## _ ## chan } + +static const dmaTimerMapping_t dmaTimerMapping[] = { + REQMAP_TIM(TMR1, CH1), + REQMAP_TIM(TMR1, CH2), + REQMAP_TIM(TMR1, CH3), + REQMAP_TIM(TMR1, CH4), + REQMAP_TIM(TMR2, CH1), + REQMAP_TIM(TMR2, CH2), + REQMAP_TIM(TMR2, CH3), + REQMAP_TIM(TMR2, CH4), + REQMAP_TIM(TMR3, CH1), + REQMAP_TIM(TMR3, CH2), + REQMAP_TIM(TMR3, CH3), + REQMAP_TIM(TMR3, CH4), + REQMAP_TIM(TMR4, CH1), + REQMAP_TIM(TMR4, CH2), + REQMAP_TIM(TMR4, CH3), + REQMAP_TIM(TMR4, CH4), + REQMAP_TIM(TMR5, CH1), + REQMAP_TIM(TMR5, CH2), + REQMAP_TIM(TMR5, CH3), + REQMAP_TIM(TMR5, CH4), + REQMAP_TIM(TMR8, CH1), + REQMAP_TIM(TMR8, CH2), + REQMAP_TIM(TMR8, CH3), + REQMAP_TIM(TMR8, CH4), + REQMAP_TIM(TMR20, CH1), + REQMAP_TIM(TMR20, CH2), + REQMAP_TIM(TMR20, CH3), + REQMAP_TIM(TMR20, CH4), + // XXX Check non-CH1 for TIM15,16,17 and 20 +}; + +#undef TC +#undef REQMAP_TIM + +#define DMA(d, c) { DMA_CODE(d, 0, c), (dmaResource_t *) DMA ## d ## _CHANNEL ## c , 0 } + +static dmaChannelSpec_t dmaChannelSpec[MAX_PERIPHERAL_DMA_OPTIONS] = { + DMA(1, 1), + DMA(1, 2), + DMA(1, 3), + DMA(1, 4), + DMA(1, 5), + DMA(1, 6), + DMA(1, 7), + DMA(2, 1), + DMA(2, 2), + DMA(2, 3), + DMA(2, 4), + DMA(2, 5), + DMA(2, 6), + DMA(2, 7), +}; + +#undef DMA + +#endif + #if defined(STM32G4) #define REQMAP_SGL(periph) { DMA_PERIPH_ ## periph, 0, DMA_REQUEST_ ## periph } @@ -480,6 +628,15 @@ static void dmaSetupRequest(dmaChannelSpec_t *dmaSpec, uint8_t request) } #endif +#if defined(AT32F4) +static void dmaSetupRequest(dmaChannelSpec_t *dmaSpec, uint8_t request) +{ + dmaSpec->dmaMuxId = request; + dmaCode_t code = dmaSpec->code; + dmaSpec->code = DMA_CODE(DMA_CODE_CONTROLLER(code), DMA_CODE_STREAM(code), dmaSpec->dmaMuxId); +} +#endif + const dmaChannelSpec_t *dmaGetChannelSpecByPeripheral(dmaPeripheral_e device, uint8_t index, int8_t opt) { if (opt < 0 || opt >= MAX_PERIPHERAL_DMA_OPTIONS) { @@ -488,7 +645,7 @@ const dmaChannelSpec_t *dmaGetChannelSpecByPeripheral(dmaPeripheral_e device, ui for (unsigned i = 0 ; i < ARRAYLEN(dmaPeripheralMapping) ; i++) { const dmaPeripheralMapping_t *periph = &dmaPeripheralMapping[i]; -#if defined(STM32H7) || defined(STM32G4) +#if defined(STM32H7) || defined(STM32G4) || defined(AT32F4) if (periph->device == device && periph->index == index) { dmaChannelSpec_t *dmaSpec = &dmaChannelSpec[opt]; dmaSetupRequest(dmaSpec, periph->dmaRequest); @@ -527,7 +684,7 @@ const dmaChannelSpec_t *dmaGetChannelSpecByTimerValue(TIM_TypeDef *tim, uint8_t for (unsigned i = 0 ; i < ARRAYLEN(dmaTimerMapping) ; i++) { const dmaTimerMapping_t *timerMapping = &dmaTimerMapping[i]; -#if defined(STM32H7) || defined(STM32G4) +#if defined(STM32H7) || defined(STM32G4) || defined(AT32F4) if (timerMapping->tim == tim && timerMapping->channel == channel) { dmaChannelSpec_t *dmaSpec = &dmaChannelSpec[dmaopt]; dmaSetupRequest(dmaSpec, timerMapping->dmaRequest); @@ -557,7 +714,7 @@ const dmaChannelSpec_t *dmaGetChannelSpecByTimer(const timerHardware_t *timer) dmaoptValue_t dmaGetOptionByTimer(const timerHardware_t *timer) { -#if defined(STM32H7) || defined(STM32G4) +#if defined(STM32H7) || defined(STM32G4) || defined(AT32F4) for (unsigned opt = 0; opt < ARRAYLEN(dmaChannelSpec); opt++) { if (timer->dmaRefConfigured == dmaChannelSpec[opt].ref) { return (dmaoptValue_t)opt; @@ -584,7 +741,7 @@ dmaoptValue_t dmaGetOptionByTimer(const timerHardware_t *timer) return DMA_OPT_UNUSED; } -#if defined(STM32H7) || defined(STM32G4) +#if defined(STM32H7) || defined(STM32G4) || defined(AT32F4) // A variant of dmaGetOptionByTimer that looks for matching dmaTimUPRef dmaoptValue_t dmaGetUpOptionByTimer(const timerHardware_t *timer) { diff --git a/src/main/drivers/dma_reqmap.h b/src/main/drivers/dma_reqmap.h index d35d05de13..5049ee6641 100644 --- a/src/main/drivers/dma_reqmap.h +++ b/src/main/drivers/dma_reqmap.h @@ -32,6 +32,8 @@ typedef struct dmaChannelSpec_s { dmaResource_t *ref; #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) uint32_t channel; +#elif defined(AT32F4) + uint32_t dmaMuxId; #endif } dmaChannelSpec_t; @@ -58,6 +60,9 @@ typedef int8_t dmaoptValue_t; #if defined(STM32H7) || defined(STM32G4) #define MAX_PERIPHERAL_DMA_OPTIONS 16 #define MAX_TIMER_DMA_OPTIONS 16 +#elif defined(AT32F4) +#define MAX_PERIPHERAL_DMA_OPTIONS 14 +#define MAX_TIMER_DMA_OPTIONS 22 #else #define MAX_PERIPHERAL_DMA_OPTIONS 2 #define MAX_TIMER_DMA_OPTIONS 3 diff --git a/src/main/drivers/exti.c b/src/main/drivers/exti.c index b7422e6d07..4ab20a1782 100644 --- a/src/main/drivers/exti.c +++ b/src/main/drivers/exti.c @@ -52,6 +52,16 @@ static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = { EXTI9_5_IRQn, EXTI15_10_IRQn }; +#elif defined(USE_ATBSP_DRIVER) +static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = { + EXINT0_IRQn, + EXINT1_IRQn, + EXINT2_IRQn, + EXINT3_IRQn, + EXINT4_IRQn, + EXINT9_5_IRQn, + EXINT15_10_IRQn +}; #else # warning "Unknown CPU" #endif @@ -65,6 +75,10 @@ static uint32_t triggerLookupTable[] = { [BETAFLIGHT_EXTI_TRIGGER_RISING] = EXTI_Trigger_Rising, [BETAFLIGHT_EXTI_TRIGGER_FALLING] = EXTI_Trigger_Falling, [BETAFLIGHT_EXTI_TRIGGER_BOTH] = EXTI_Trigger_Rising_Falling +#elif defined(AT32F4) + [BETAFLIGHT_EXTI_TRIGGER_RISING] = EXINT_TRIGGER_RISING_EDGE, + [BETAFLIGHT_EXTI_TRIGGER_FALLING] = EXINT_TRIGGER_FALLING_EDGE, + [BETAFLIGHT_EXTI_TRIGGER_BOTH] = EXINT_TRIGGER_BOTH_EDGE #else # warning "Unknown CPU" #endif @@ -78,6 +92,9 @@ static uint32_t triggerLookupTable[] = { #elif defined(STM32G4) #define EXTI_REG_IMR (EXTI->IMR1) #define EXTI_REG_PR (EXTI->PR1) +#elif defined(USE_ATBSP_DRIVER) +#define EXTI_REG_IMR (EXINT->inten) +#define EXTI_REG_PR (EXINT->intsts) #else #define EXTI_REG_IMR (EXTI->IMR) #define EXTI_REG_PR (EXTI->PR) @@ -94,7 +111,10 @@ void EXTIInit(void) #ifdef REMAP_TIM17_DMA SYSCFG_DMAChannelRemapConfig(SYSCFG_DMARemap_TIM17, ENABLE); #endif +#elif defined(USE_ATBSP_DRIVER) + crm_periph_clock_enable(CRM_SCFG_PERIPH_CLOCK, TRUE); #endif + memset(extiChannelRecs, 0, sizeof(extiChannelRecs)); memset(extiGroupPriority, 0xff, sizeof(extiGroupPriority)); } @@ -138,9 +158,7 @@ void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, ioConfig_t conf #if defined(STM32F4) SYSCFG_EXTILineConfig(IO_EXTI_PortSourceGPIO(io), IO_EXTI_PinSource(io)); -#else -# warning "Unknown CPU" -#endif + uint32_t extiLine = IO_EXTI_Line(io); EXTI_InitTypeDef EXTIInit; @@ -160,6 +178,35 @@ void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, ioConfig_t conf NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); } +#elif defined(USE_ATBSP_DRIVER) + scfg_exint_line_config(IO_GPIO_PortSource(io), IO_GPIO_PinSource(io)); + + uint32_t extiLine = IO_EXTI_Line(io); + + exint_flag_clear(extiLine); + + exint_init_type exint_init_struct; + exint_default_para_init(&exint_init_struct); + exint_init_struct.line_enable = TRUE; + exint_init_struct.line_mode = EXINT_LINE_INTERRUPUT; + exint_init_struct.line_select = extiLine; + exint_init_struct.line_polarity = triggerLookupTable[trigger]; + exint_init(&exint_init_struct); + + if (extiGroupPriority[group] > irqPriority) { + extiGroupPriority[group] = irqPriority; + + nvic_priority_group_config(NVIC_PRIORITY_GROUPING); + nvic_irq_enable( + extiGroupIRQn[group], + NVIC_PRIORITY_BASE(irqPriority), + NVIC_PRIORITY_SUB(irqPriority) + ); + } +#else +# warning "Unknown CPU" +#endif + #endif } @@ -180,7 +227,7 @@ void EXTIRelease(IO_t io) void EXTIEnable(IO_t io) { -#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) uint32_t extiLine = IO_EXTI_Line(io); if (!extiLine) { @@ -196,7 +243,7 @@ void EXTIEnable(IO_t io) void EXTIDisable(IO_t io) { -#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) uint32_t extiLine = IO_EXTI_Line(io); if (!extiLine) { @@ -237,7 +284,7 @@ void EXTI_IRQHandler(uint32_t mask) _EXTI_IRQ_HANDLER(EXTI0_IRQHandler, 0x0001); _EXTI_IRQ_HANDLER(EXTI1_IRQHandler, 0x0002); -#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) _EXTI_IRQ_HANDLER(EXTI2_IRQHandler, 0x0004); #else # warning "Unknown CPU" @@ -248,4 +295,3 @@ _EXTI_IRQ_HANDLER(EXTI9_5_IRQHandler, 0x03e0); _EXTI_IRQ_HANDLER(EXTI15_10_IRQHandler, 0xfc00); #endif - diff --git a/src/main/drivers/io.c b/src/main/drivers/io.c index 88667a73e6..e2a95179b5 100644 --- a/src/main/drivers/io.c +++ b/src/main/drivers/io.c @@ -72,6 +72,21 @@ const struct ioPortDef_s ioPortDefs[] = { { RCC_AHB2(GPIOE) }, { RCC_AHB2(GPIOF) }, }; +#elif defined(AT32F4) +const struct ioPortDef_s ioPortDefs[] = { + { RCC_AHB1(GPIOA) }, + { RCC_AHB1(GPIOB) }, + { RCC_AHB1(GPIOC) }, + { RCC_AHB1(GPIOD) }, + { RCC_AHB1(GPIOE) }, + { RCC_AHB1(GPIOF) }, + { RCC_AHB1(GPIOG) }, + { RCC_AHB1(GPIOH) } +}; +#elif defined(SITL) +const struct ioPortDef_s ioPortDefs[] = { 0 }; +#else +# error "IO PortDefs not defined for MCU" #endif ioRec_t* IO_Rec(IO_t io) @@ -135,7 +150,7 @@ uint32_t IO_EXTI_Line(IO_t io) if (!io) { return 0; } -#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) return 1 << IO_GPIOPinIdx(io); #elif defined(SIMULATOR_BUILD) return 0; @@ -153,6 +168,8 @@ bool IORead(IO_t io) return (LL_GPIO_ReadInputPort(IO_GPIO(io)) & IO_Pin(io)); #elif defined(USE_HAL_DRIVER) return !! HAL_GPIO_ReadPin(IO_GPIO(io), IO_Pin(io)); +#elif defined(USE_ATBSP_DRIVER) + return (IO_GPIO(io)->idt & IO_Pin(io)); #else return (IO_GPIO(io)->IDR & IO_Pin(io)); #endif @@ -173,6 +190,8 @@ void IOWrite(IO_t io, bool hi) } else { IO_GPIO(io)->BSRRH = IO_Pin(io); } +#elif defined(USE_ATBSP_DRIVER) + IO_GPIO(io)->scr = IO_Pin(io) << (hi ? 0 : 16); #else IO_GPIO(io)->BSRR = IO_Pin(io) << (hi ? 0 : 16); #endif @@ -189,6 +208,8 @@ void IOHi(IO_t io) HAL_GPIO_WritePin(IO_GPIO(io), IO_Pin(io), GPIO_PIN_SET); #elif defined(STM32F4) IO_GPIO(io)->BSRRL = IO_Pin(io); +#elif defined(USE_ATBSP_DRIVER) + IO_GPIO(io)->scr = IO_Pin(io); #else IO_GPIO(io)->BSRR = IO_Pin(io); #endif @@ -205,6 +226,8 @@ void IOLo(IO_t io) HAL_GPIO_WritePin(IO_GPIO(io), IO_Pin(io), GPIO_PIN_RESET); #elif defined(STM32F4) IO_GPIO(io)->BSRRH = IO_Pin(io); +#elif defined(USE_ATBSP_DRIVER) + IO_GPIO(io)->clr = IO_Pin(io); #else IO_GPIO(io)->BRR = IO_Pin(io); #endif @@ -234,10 +257,15 @@ void IOToggle(IO_t io) } else { IO_GPIO(io)->BSRRL = mask; } +#elif defined(USE_ATBSP_DRIVER) + if (IO_GPIO(io)->odt & mask) { + mask <<= 16; // bit is set, shift mask to reset half + } + IO_GPIO(io)->scr = mask; #else - if (IO_GPIO(io)->ODR & mask) - mask <<= 16; // bit is set, shift mask to reset half - + if (IO_GPIO(io)->ODR & mask) { + mask <<= 16; // bit is set, shift mask to reset half + } IO_GPIO(io)->BSRR = mask; #endif } @@ -377,6 +405,49 @@ void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af) }; GPIO_Init(IO_GPIO(io), &init); } + +#elif defined(AT32F4) + +//TODO: move to specific files (applies to STM32 also) +void IOConfigGPIO(IO_t io, ioConfig_t cfg) +{ + if (!io) { + return; + } + + const rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc; + RCC_ClockCmd(rcc, ENABLE); + + gpio_init_type init = { + .gpio_pins = IO_Pin(io), + .gpio_mode = (cfg >> 0) & 0x03, + .gpio_drive_strength = (cfg >> 2) & 0x03, + .gpio_out_type = (cfg >> 4) & 0x01, + .gpio_pull = (cfg >> 5) & 0x03, + }; + gpio_init(IO_GPIO(io), &init); +} + +void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af) +{ + if (!io) { + return; + } + + const rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc; + RCC_ClockCmd(rcc, ENABLE); + + gpio_init_type init = { + .gpio_pins = IO_Pin(io), + .gpio_mode = (cfg >> 0) & 0x03, + .gpio_drive_strength = (cfg >> 2) & 0x03, + .gpio_out_type = (cfg >> 4) & 0x01, + .gpio_pull = (cfg >> 5) & 0x03, + }; + gpio_init(IO_GPIO(io), &init); + gpio_pin_mux_config(IO_GPIO(io), IO_GPIO_PinSource(io), af); +} + #endif #if DEFIO_PORT_USED_COUNT > 0 diff --git a/src/main/drivers/io.h b/src/main/drivers/io.h index 61905cc544..574c245d1a 100644 --- a/src/main/drivers/io.h +++ b/src/main/drivers/io.h @@ -71,21 +71,39 @@ #define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_NOPULL) #define IOCFG_IPU_25 IO_CONFIG(GPIO_Mode_IN, GPIO_Speed_25MHz, 0, GPIO_PuPd_UP) +#elif defined(AT32F4) + +#define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5)) + +#define IOCFG_OUT_PP IO_CONFIG(GPIO_MODE_OUTPUT , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_NONE ) // TODO +#define IOCFG_OUT_PP_UP IO_CONFIG(GPIO_MODE_OUTPUT , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_UP ) +#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_MODE_OUTPUT , GPIO_DRIVE_STRENGTH_STRONGER , GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_NONE) +#define IOCFG_OUT_OD IO_CONFIG(GPIO_MODE_OUTPUT , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_OPEN_DRAIN , GPIO_PULL_NONE) +#define IOCFG_AF_PP IO_CONFIG(GPIO_MODE_MUX , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_NONE) +#define IOCFG_AF_PP_PD IO_CONFIG(GPIO_MODE_MUX , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_DOWN) +#define IOCFG_AF_PP_UP IO_CONFIG(GPIO_MODE_MUX , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_UP) +#define IOCFG_AF_OD IO_CONFIG(GPIO_MODE_MUX , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_OPEN_DRAIN , GPIO_PULL_NONE) +#define IOCFG_IPD IO_CONFIG(GPIO_MODE_INPUT , GPIO_DRIVE_STRENGTH_MODERATE, 0, GPIO_PULL_DOWN) +#define IOCFG_IPU IO_CONFIG(GPIO_MODE_INPUT , GPIO_DRIVE_STRENGTH_MODERATE, 0, GPIO_PULL_UP) +#define IOCFG_IN_FLOATING IO_CONFIG(GPIO_MODE_INPUT , GPIO_DRIVE_STRENGTH_MODERATE, 0, GPIO_PULL_NONE) +#define IOCFG_IPU_25 IO_CONFIG(GPIO_MODE_INPUT , GPIO_DRIVE_STRENGTH_MODERATE , 0, GPIO_PULL_UP) + + #elif defined(UNIT_TEST) || defined(SIMULATOR_BUILD) -# define IOCFG_OUT_PP 0 -# define IOCFG_OUT_OD 0 -# define IOCFG_AF_PP 0 -# define IOCFG_AF_OD 0 -# define IOCFG_IPD 0 -# define IOCFG_IPU 0 -# define IOCFG_IN_FLOATING 0 +#define IOCFG_OUT_PP 0 +#define IOCFG_OUT_OD 0 +#define IOCFG_AF_PP 0 +#define IOCFG_AF_OD 0 +#define IOCFG_IPD 0 +#define IOCFG_IPU 0 +#define IOCFG_IN_FLOATING 0 #else # warning "Unknown TARGET" #endif -#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) +#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) // Expose these for EXTIConfig #define IO_CONFIG_GET_MODE(cfg) (((cfg) >> 0) & 0x03) #define IO_CONFIG_GET_SPEED(cfg) (((cfg) >> 2) & 0x03) @@ -109,7 +127,7 @@ bool IOIsFreeOrPreinit(IO_t io); IO_t IOGetByTag(ioTag_t tag); void IOConfigGPIO(IO_t io, ioConfig_t cfg); -#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) +#ifdef USE_TIMER_AF void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af); #endif diff --git a/src/main/drivers/nvic.h b/src/main/drivers/nvic.h index ed3c65629b..e1c270213f 100644 --- a/src/main/drivers/nvic.h +++ b/src/main/drivers/nvic.h @@ -83,6 +83,11 @@ #define NVIC_BUILD_PRIORITY(base,sub) (((((base)<<(4-(7-(NVIC_PRIORITY_GROUPING))))|((sub)&(0x0f>>(7-(NVIC_PRIORITY_GROUPING)))))<<4)&0xf0) #define NVIC_PRIORITY_BASE(prio) (((prio)>>(4-(7-(NVIC_PRIORITY_GROUPING))))>>4) #define NVIC_PRIORITY_SUB(prio) (((prio)&(0x0f>>(7-(NVIC_PRIORITY_GROUPING))))>>4) +#elif defined(USE_ATBSP_DRIVER) +#define NVIC_PRIORITY_GROUPING NVIC_PRIORITY_GROUP_2 +#define NVIC_BUILD_PRIORITY(base,sub) (((((base)<<(4-(7-(NVIC_PRIORITY_GROUPING))))|((sub)&(0x0f>>(7-(NVIC_PRIORITY_GROUPING)))))<<4)&0xf0) +#define NVIC_PRIORITY_BASE(prio) (((prio)>>(4-(7-(NVIC_PRIORITY_GROUPING))))>>4) +#define NVIC_PRIORITY_SUB(prio) (((prio)&((0x0f>>(7-(NVIC_PRIORITY_GROUPING)))<<4))>>4) #else // utility macros to join/split priority #define NVIC_PRIORITY_GROUPING NVIC_PriorityGroup_2 diff --git a/src/main/drivers/rcc.c b/src/main/drivers/rcc.c index 6b0198a768..130d563247 100644 --- a/src/main/drivers/rcc.c +++ b/src/main/drivers/rcc.c @@ -111,6 +111,44 @@ void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState) #endif } +#elif defined(USE_ATBSP_DRIVER) + +#define NOSUFFIX // Empty + +#define __AT_RCC_CLK_ENABLE(bus, suffix, enbit) do { \ + __IO uint32_t tmpreg; \ + SET_BIT(CRM->bus ## en ## suffix, enbit); \ + /* Delay after an RCC peripheral clock enabling */ \ + tmpreg = READ_BIT(CRM->bus ## en ## suffix, enbit); \ + UNUSED(tmpreg); \ + } while(0) + +#define __AT_RCC_CLK_DISABLE(bus, suffix, enbit) (CRM->bus ## en ## suffix &= ~(enbit)) + +#define __AT_RCC_CLK(bus, suffix, enbit, newState) \ + if (newState == ENABLE) { \ + __AT_RCC_CLK_ENABLE(bus, suffix, enbit); \ + } else { \ + __AT_RCC_CLK_DISABLE(bus, suffix, enbit); \ + } + + switch (tag) { + case RCC_AHB1: + __AT_RCC_CLK(ahb, 1, mask, NewState); + break; + case RCC_AHB2: + __AT_RCC_CLK(ahb, 2, mask, NewState); + break; + case RCC_AHB3: + __AT_RCC_CLK(ahb, 3, mask, NewState); + break; + case RCC_APB1: + __AT_RCC_CLK(apb1, NOSUFFIX, mask, NewState); + break; + case RCC_APB2: + __AT_RCC_CLK(apb2, NOSUFFIX, mask, NewState); + break; + } #else switch (tag) { case RCC_APB2: @@ -204,7 +242,33 @@ void RCC_ResetCmd(rccPeriphTag_t periphTag, FunctionalState NewState) #endif } +#elif defined(USE_ATBSP_DRIVER) +#define __AT_RCC_FORCE_RESET(bus, suffix, enbit) (CRM->bus ## rst ## suffix |= (enbit)) +#define __AT_RCC_RELEASE_RESET(bus, suffix, enbit) (CRM->bus ## rst ## suffix &= ~(enbit)) +#define __AT_RCC_RESET(bus, suffix, enbit, NewState) \ + if (NewState == ENABLE) { \ + __AT_RCC_RELEASE_RESET(bus, suffix, enbit); \ + } else { \ + __AT_RCC_FORCE_RESET(bus, suffix, enbit); \ + } + switch (tag) { + case RCC_AHB1: + __AT_RCC_RESET(ahb, 1, mask, NewState); + break; + case RCC_AHB2: + __AT_RCC_RESET(ahb, 2, mask, NewState); + break; + case RCC_AHB3: + __AT_RCC_RESET(ahb, 3, mask, NewState); + break; + case RCC_APB1: + __AT_RCC_RESET(apb1, NOSUFFIX, mask, NewState); + break; + case RCC_APB2: + __AT_RCC_RESET(apb2, NOSUFFIX, mask, NewState); + break; + } #else switch (tag) { diff --git a/src/main/drivers/rcc.h b/src/main/drivers/rcc.h index f25cac1f97..21b2c5913a 100644 --- a/src/main/drivers/rcc.h +++ b/src/main/drivers/rcc.h @@ -46,6 +46,12 @@ enum rcc_reg { RCC_APB11, RCC_APB12, RCC_AHB1, +#elif defined(AT32F4) + RCC_AHB1, + RCC_AHB2, + RCC_AHB3, + RCC_APB2, + RCC_APB1, #else RCC_AHB, RCC_APB2, @@ -55,35 +61,46 @@ enum rcc_reg { }; #define RCC_ENCODE(reg, mask) (((reg) << 5) | LOG2_32BIT(mask)) + +#if defined(STM32F4) #define RCC_AHB(periph) RCC_ENCODE(RCC_AHB, RCC_AHBENR_ ## periph ## EN) #define RCC_APB2(periph) RCC_ENCODE(RCC_APB2, RCC_APB2ENR_ ## periph ## EN) #define RCC_APB1(periph) RCC_ENCODE(RCC_APB1, RCC_APB1ENR_ ## periph ## EN) #define RCC_AHB1(periph) RCC_ENCODE(RCC_AHB1, RCC_AHB1ENR_ ## periph ## EN) - -#ifdef STM32H7 +#elif defined(STM32H7) +#define RCC_AHB(periph) RCC_ENCODE(RCC_AHB, RCC_AHBENR_ ## periph ## EN) +#define RCC_APB2(periph) RCC_ENCODE(RCC_APB2, RCC_APB2ENR_ ## periph ## EN) +#define RCC_AHB1(periph) RCC_ENCODE(RCC_AHB1, RCC_AHB1ENR_ ## periph ## EN) #define RCC_AHB2(periph) RCC_ENCODE(RCC_AHB2, RCC_AHB2ENR_ ## periph ## EN) #define RCC_AHB3(periph) RCC_ENCODE(RCC_AHB3, RCC_AHB3ENR_ ## periph ## EN) #define RCC_APB3(periph) RCC_ENCODE(RCC_APB3, RCC_APB3ENR_ ## periph ## EN) #define RCC_AHB4(periph) RCC_ENCODE(RCC_AHB4, RCC_AHB4ENR_ ## periph ## EN) #define RCC_APB4(periph) RCC_ENCODE(RCC_APB4, RCC_APB4ENR_ ## periph ## EN) -#undef RCC_APB1 #define RCC_APB1L(periph) RCC_ENCODE(RCC_APB1L, RCC_APB1LENR_ ## periph ## EN) #define RCC_APB1H(periph) RCC_ENCODE(RCC_APB1H, RCC_APB1HENR_ ## periph ## EN) -#endif - -#ifdef STM32G4 -#undef RCC_APB1 +#elif defined(STM32G4) +#define RCC_AHB(periph) RCC_ENCODE(RCC_AHB, RCC_AHBENR_ ## periph ## EN) +#define RCC_APB2(periph) RCC_ENCODE(RCC_APB2, RCC_APB2ENR_ ## periph ## EN) +#define RCC_AHB1(periph) RCC_ENCODE(RCC_AHB1, RCC_AHB1ENR_ ## periph ## EN) #define RCC_APB11(periph) RCC_ENCODE(RCC_APB11, RCC_APB1ENR1_ ## periph ## EN) #define RCC_APB12(periph) RCC_ENCODE(RCC_APB12, RCC_APB1ENR2_ ## periph ## EN) #define RCC_AHB1(periph) RCC_ENCODE(RCC_AHB1, RCC_AHB1ENR_ ## periph ## EN) #define RCC_AHB2(periph) RCC_ENCODE(RCC_AHB2, RCC_AHB2ENR_ ## periph ## EN) -#endif - -#ifdef STM32F7 +#elif defined(STM32F7) +#define RCC_AHB(periph) RCC_ENCODE(RCC_AHB, RCC_AHBENR_ ## periph ## EN) +#define RCC_APB2(periph) RCC_ENCODE(RCC_APB2, RCC_APB2ENR_ ## periph ## EN) +#define RCC_APB1(periph) RCC_ENCODE(RCC_APB1, RCC_APB1ENR_ ## periph ## EN) +#define RCC_AHB1(periph) RCC_ENCODE(RCC_AHB1, RCC_AHB1ENR_ ## periph ## EN) #define RCC_AHB1(periph) RCC_ENCODE(RCC_AHB1, RCC_AHB1ENR_ ## periph ## EN) #define RCC_AHB2(periph) RCC_ENCODE(RCC_AHB2, RCC_AHB2ENR_ ## periph ## EN) #define RCC_APB1(periph) RCC_ENCODE(RCC_APB1, RCC_APB1ENR_ ## periph ## EN) #define RCC_APB2(periph) RCC_ENCODE(RCC_APB2, RCC_APB2ENR_ ## periph ## EN) +#elif defined(AT32F4) +#define RCC_AHB1(periph) RCC_ENCODE(RCC_AHB1, CRM_AHB1_ ## periph ## _PER_MASK) +#define RCC_AHB2(periph) RCC_ENCODE(RCC_AHB2, CRM_AHB2_ ## periph ## _PER_MASK) +#define RCC_AHB3(periph) RCC_ENCODE(RCC_AHB3, CRM_AHB3_ ## periph ## _PER_MASK) +#define RCC_APB1(periph) RCC_ENCODE(RCC_APB1, CRM_APB1_ ## periph ## _PER_MASK) +#define RCC_APB2(periph) RCC_ENCODE(RCC_APB2, CRM_APB2_ ## periph ## _PER_MASK) #endif void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState); diff --git a/src/main/drivers/serial_uart.c b/src/main/drivers/serial_uart.c index b03b80a0ee..6de5761a47 100644 --- a/src/main/drivers/serial_uart.c +++ b/src/main/drivers/serial_uart.c @@ -54,7 +54,7 @@ #elif defined(STM32F7) #define UART_TX_BUFFER_ATTRIBUTE FAST_DATA_ZERO_INIT // DTCM RAM #define UART_RX_BUFFER_ATTRIBUTE FAST_DATA_ZERO_INIT // DTCM RAM -#elif defined(STM32F4) +#elif defined(STM32F4) || defined(AT32F4) #define UART_TX_BUFFER_ATTRIBUTE // NONE #define UART_RX_BUFFER_ATTRIBUTE // NONE #else @@ -281,8 +281,10 @@ static void uartWrite(serialPort_t *instance, uint8_t ch) } else #endif { -#ifdef USE_HAL_DRIVER +#if defined(USE_HAL_DRIVER) __HAL_UART_ENABLE_IT(&uartPort->Handle, UART_IT_TXE); +#elif defined(USE_ATBSP_DRIVER) + usart_interrupt_enable(uartPort->USARTx, USART_TDBE_INT, TRUE); #else USART_ITConfig(uartPort->USARTx, USART_IT_TXE, ENABLE); #endif @@ -320,7 +322,11 @@ void uartConfigureDma(uartDevice_t *uartdev) dmaChannelSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_UART_TX, device, serialUartConfig(device)->txDmaopt); if (dmaChannelSpec) { uartPort->txDMAResource = dmaChannelSpec->ref; +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) uartPort->txDMAChannel = dmaChannelSpec->channel; +#elif defined(AT32F4) + uartPort->txDMAMuxId = dmaChannelSpec->dmaMuxId; +#endif } } @@ -328,7 +334,11 @@ void uartConfigureDma(uartDevice_t *uartdev) dmaChannelSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_UART_RX, device, serialUartConfig(device)->txDmaopt); if (dmaChannelSpec) { uartPort->rxDMAResource = dmaChannelSpec->ref; +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) uartPort->rxDMAChannel = dmaChannelSpec->channel; +#elif defined(AT32F4) + uartPort->rxDMAMuxId = dmaChannelSpec->dmaMuxId; +#endif } } #else @@ -336,12 +346,20 @@ void uartConfigureDma(uartDevice_t *uartdev) if (hardware->rxDMAResource) { uartPort->rxDMAResource = hardware->rxDMAResource; +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) uartPort->rxDMAChannel = hardware->rxDMAChannel; +#elif defined(AT32F4) + uartPort->rxDMAMuxId = hardware->rxDMAMuxId; +#endif } if (hardware->txDMAResource) { uartPort->txDMAResource = hardware->txDMAResource; +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) uartPort->txDMAChannel = hardware->txDMAChannel; +#elif defined(AT32F4) + uartPort->txDMAMuxId = hardware->txDMAMuxId; +#endif } #endif @@ -349,6 +367,9 @@ void uartConfigureDma(uartDevice_t *uartdev) dmaIdentifier_e identifier = dmaGetIdentifier(uartPort->txDMAResource); if (dmaAllocate(identifier, OWNER_SERIAL_TX, RESOURCE_INDEX(hardware->device))) { dmaEnable(identifier); +#if defined(AT32F4) + dmaMuxEnable(identifier, uartPort->txDMAMuxId); +#endif dmaSetHandler(identifier, uartDmaIrqHandler, hardware->txPriority, (uint32_t)uartdev); uartPort->txDMAPeripheralBaseAddr = (uint32_t)&UART_REG_TXD(hardware->reg); } @@ -358,6 +379,9 @@ void uartConfigureDma(uartDevice_t *uartdev) dmaIdentifier_e identifier = dmaGetIdentifier(uartPort->rxDMAResource); if (dmaAllocate(identifier, OWNER_SERIAL_RX, RESOURCE_INDEX(hardware->device))) { dmaEnable(identifier); +#if defined(AT32F4) + dmaMuxEnable(identifier, uartPort->rxDMAMuxId); +#endif uartPort->rxDMAPeripheralBaseAddr = (uint32_t)&UART_REG_RXD(hardware->reg); } } diff --git a/src/main/drivers/serial_uart.h b/src/main/drivers/serial_uart.h index b9351355a9..c1da6a82bc 100644 --- a/src/main/drivers/serial_uart.h +++ b/src/main/drivers/serial_uart.h @@ -56,6 +56,10 @@ typedef struct uartPort_s { dmaResource_t *txDMAResource; uint32_t rxDMAChannel; uint32_t txDMAChannel; +#if defined(USE_ATBSP_DRIVER) + uint32_t rxDMAMuxId; + uint32_t txDMAMuxId; +#endif uint32_t rxDMAIrq; uint32_t txDMAIrq; diff --git a/src/main/drivers/serial_uart_impl.h b/src/main/drivers/serial_uart_impl.h index 87e55230c7..59581fcf13 100644 --- a/src/main/drivers/serial_uart_impl.h +++ b/src/main/drivers/serial_uart_impl.h @@ -74,6 +74,19 @@ #define UART_TX_BUFFER_SIZE 256 #endif #endif +#elif defined(AT32F4) +#define UARTDEV_COUNT_MAX 8 // UARTs 1 to 5 + LPUART1 (index 9) +#define UARTHARDWARE_MAX_PINS 5 +#ifndef UART_RX_BUFFER_SIZE +#define UART_RX_BUFFER_SIZE 128 +#endif +#ifndef UART_TX_BUFFER_SIZE +#ifdef USE_MSP_DISPLAYPORT +#define UART_TX_BUFFER_SIZE 1280 +#else +#define UART_TX_BUFFER_SIZE 256 +#endif +#endif #else #error unknown MCU family #endif @@ -150,7 +163,7 @@ typedef struct uartPinDef_s { ioTag_t pin; -#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) +#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F43x) uint8_t af; #endif } uartPinDef_t; @@ -162,10 +175,17 @@ typedef struct uartHardware_s { #ifdef USE_DMA dmaResource_t *txDMAResource; dmaResource_t *rxDMAResource; - // For H7 and G4, {tx|rx}DMAChannel are DMAMUX input index for peripherals (DMA_REQUEST_xxx); H7:RM0433 Table 110, G4:RM0440 Table 80. - // For F4 and F7, these are 32-bit channel identifiers (DMA_CHANNEL_x). + // For H7 and G4 , {tx|rx}DMAChannel are DMAMUX input index for peripherals (DMA_REQUEST_xxx); H7:RM0433 Table 110, G4:RM0440 Table 80. + // For F4 and F7, these are 32-bit channel identifiers (DMA_CHANNEL_x) + // For at32f435/7 DmaChannel is the dmamux ,need to call dmamuxenable using dmamuxid +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) uint32_t txDMAChannel; uint32_t rxDMAChannel; +#elif defined(AT32F4) + uint32_t txDMAMuxId;//for dmaspec->dmamux and using dmaMuxEnable(dmax,muxid) + uint32_t rxDMAMuxId; +#endif + #endif // USE_DMA uartPinDef_t rxPins[UARTHARDWARE_MAX_PINS]; @@ -231,6 +251,9 @@ void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor); #elif defined(STM32F4) #define UART_REG_RXD(base) ((base)->DR) #define UART_REG_TXD(base) ((base)->DR) +#elif defined(AT32F43x) +#define UART_REG_RXD(base) ((base)->dt) +#define UART_REG_TXD(base) ((base)->dt) #endif #define UART_BUFFER(type, n, rxtx) type volatile uint8_t uart ## n ## rxtx ## xBuffer[UART_ ## rxtx ## X_BUFFER_SIZE] diff --git a/src/main/drivers/system.c b/src/main/drivers/system.c index b17522d848..ab0e8988da 100644 --- a/src/main/drivers/system.c +++ b/src/main/drivers/system.c @@ -35,7 +35,7 @@ #include "system.h" -#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(AT32F4) // See "RM CoreSight Architecture Specification" // B2.3.10 "LSR and LAR, Software Lock Status Register and Software Lock Access Register" // "E1.2.11 LAR, Lock Access Register" @@ -57,6 +57,10 @@ void cycleCounterInit(void) { #if defined(USE_HAL_DRIVER) cpuClockFrequency = HAL_RCC_GetSysClockFreq(); +#elif defined(USE_ATBSP_DRIVER) + crm_clocks_freq_type clocks; + crm_clocks_freq_get(&clocks); + cpuClockFrequency = clocks.sclk_freq; #else RCC_ClocksTypeDef clocks; RCC_GetClocksFreq(&clocks); @@ -67,7 +71,7 @@ void cycleCounterInit(void) CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk; #if defined(DWT_LAR_UNLOCK_VALUE) -#if defined(STM32H7) +#if defined(STM32H7) || defined(AT32F4) ITM->LAR = DWT_LAR_UNLOCK_VALUE; #elif defined(STM32F7) DWT->LAR = DWT_LAR_UNLOCK_VALUE; diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index 6f218371db..1455c501ea 100644 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -67,6 +67,7 @@ typedef struct timerConfig_s { timerOvrHandlerRec_t *overflowCallbackActive; // null-terminated linked list of active overflow callbacks uint32_t forcedOverflowTimerValue; } timerConfig_t; + timerConfig_t timerConfig[USED_TIMER_COUNT]; typedef struct { diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index 50b8304469..c8aa9015f5 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -27,7 +27,11 @@ #include "drivers/io_types.h" #include "drivers/rcc_types.h" #include "drivers/resource.h" +#if defined(USE_ATBSP_DRIVER) +#include "drivers/at32/timer_def_at32.h" +#else #include "drivers/timer_def.h" +#endif #include "pg/timerio.h" @@ -37,14 +41,10 @@ typedef uint16_t captureCompare_t; // 16 bit on both 103 and 303, just register access must be 32bit sometimes (use timCCR_t) -#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(UNIT_TEST) || defined(SIMULATOR_BUILD) typedef uint32_t timCCR_t; typedef uint32_t timCCER_t; typedef uint32_t timSR_t; typedef uint32_t timCNT_t; -#else -#error "Unknown CPU defined" -#endif typedef enum { TIM_USE_ANY = 0x0, @@ -86,25 +86,25 @@ typedef struct timerHardware_s { uint8_t channel; timerUsageFlag_e usageFlags; uint8_t output; -#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) +#if defined(USE_TIMER_AF) uint8_t alternateFunction; #endif #if defined(USE_TIMER_DMA) #if defined(USE_DMA_SPEC) -#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) dmaResource_t *dmaRefConfigured; uint32_t dmaChannelConfigured; #endif #else // USE_DMA_SPEC dmaResource_t *dmaRef; -#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) uint32_t dmaChannel; // XXX Can be much smaller (e.g. uint8_t) #endif #endif // USE_DMA_SPEC dmaResource_t *dmaTimUPRef; -#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) uint32_t dmaTimUPChannel; #endif uint8_t dmaTimUPIrqHandler; @@ -182,8 +182,6 @@ extern const timerHardware_t fullTimerHardware[]; #define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(6) | TIM_N(7) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17) | TIM_N(20) ) -#else - #error "No timer / channel tag definition found for CPU" #endif #else diff --git a/src/main/fc/init.c b/src/main/fc/init.c index 3ab56faf26..7a3191c36e 100644 --- a/src/main/fc/init.c +++ b/src/main/fc/init.c @@ -293,7 +293,7 @@ void init(void) enum { FLASH_INIT_ATTEMPTED = (1 << 0), SD_INIT_ATTEMPTED = (1 << 1), - SPI_AND_QSPI_INIT_ATTEMPTED = (1 << 2), + SPI_AND_QSPI_INIT_ATTEMPTED = (1 << 2), }; uint8_t initFlags = 0; diff --git a/src/main/io/flashfs.c b/src/main/io/flashfs.c index 55a549ee5d..06f53f9b88 100644 --- a/src/main/io/flashfs.c +++ b/src/main/io/flashfs.c @@ -38,6 +38,8 @@ #include "platform.h" +#if defined(USE_FLASHFS) + #include "build/debug.h" #include "common/printf.h" #include "drivers/flash.h" @@ -666,3 +668,4 @@ bool flashfsVerifyEntireFlash(void) return verificationFailures == 0; } #endif // USE_FLASH_TOOLS +#endif // USE_FLASHFS diff --git a/src/main/io/serial.c b/src/main/io/serial.c index 8a76e06372..3df1e74c9b 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -158,12 +158,10 @@ void pgResetFn_serialConfig(serialConfig_t *serialConfig) } #endif -#if defined(USE_VCP) && defined(USE_MSP_UART) - if (serialConfig->portConfigs[0].identifier == SERIAL_PORT_USB_VCP) { - serialPortConfig_t * uart1Config = serialFindPortConfigurationMutable(SERIAL_PORT_USART1); - if (uart1Config) { - uart1Config->functionMask = FUNCTION_MSP; - } +#if defined(USE_MSP_UART) + serialPortConfig_t * uart1Config = serialFindPortConfigurationMutable(USE_MSP_UART); + if (uart1Config) { + uart1Config->functionMask = FUNCTION_MSP; } #endif diff --git a/src/main/io/serial.h b/src/main/io/serial.h index 61dd6bab46..497d3c352a 100644 --- a/src/main/io/serial.h +++ b/src/main/io/serial.h @@ -102,7 +102,6 @@ typedef enum { extern const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT]; #define SERIAL_PORT_IDENTIFIER_TO_INDEX(x) (((x) < RESOURCE_SOFT_OFFSET) ? (x) : (RESOURCE_SOFT_OFFSET + ((x) - SERIAL_PORT_SOFTSERIAL1))) - #define SERIAL_PORT_IDENTIFIER_TO_UARTDEV(x) ((x) - SERIAL_PORT_USART1 + UARTDEV_1) // diff --git a/src/main/platform.h b/src/main/platform.h index 3b3e19dd44..00b01bc24e 100644 --- a/src/main/platform.h +++ b/src/main/platform.h @@ -26,6 +26,9 @@ #pragma GCC poison sprintf snprintf #endif +// common to all +#define USE_TIMER_AF + #if defined(STM32G474xx) #include "stm32g4xx.h" #include "stm32g4xx_hal.h" @@ -45,6 +48,8 @@ #define U_ID_1 (*(uint32_t*)(UID_BASE + 4)) #define U_ID_2 (*(uint32_t*)(UID_BASE + 8)) +#define USE_PIN_AF + #ifndef STM32G4 #define STM32G4 #endif @@ -68,6 +73,8 @@ #define U_ID_1 (*(uint32_t*)(UID_BASE + 4)) #define U_ID_2 (*(uint32_t*)(UID_BASE + 8)) +#define USE_PIN_AF + #ifndef STM32H7 #define STM32H7 #endif @@ -91,6 +98,8 @@ #define U_ID_1 (*(uint32_t*)(UID_BASE + 4)) #define U_ID_2 (*(uint32_t*)(UID_BASE + 8)) +#define USE_PIN_AF + #ifndef STM32F7 #define STM32F7 #endif @@ -108,9 +117,52 @@ #define STM32F4 #endif +#elif defined(AT32F435ZMT7) + +#include "at32f435_437.h" + +typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; + +#define GPIO_TypeDef gpio_type +#define GPIO_InitTypeDef gpio_init_type +#define TIM_TypeDef tmr_type +#define TIM_OCInitTypeDef tmr_output_config_type +#define DMA_TypeDef dma_type +#define DMA_InitTypeDef dma_init_type +#define DMA_Channel_TypeDef dma_channel_type +#define SPI_TypeDef spi_type +#define ADC_TypeDef adc_type +#define USART_TypeDef usart_type +#define TIM_OCInitTypeDef tmr_output_config_type +#define TIM_ICInitTypeDef tmr_input_config_type +#define SystemCoreClock system_core_clock +#define EXTI_TypeDef exint_type +#define EXTI_InitTypeDef exint_init_type +#define USART_TypeDef usart_type + +// Chip Unique ID on F43X +#define U_ID_0 (*(uint32_t*)0x1ffff7e8) +#define U_ID_1 (*(uint32_t*)0x1ffff7ec) +#define U_ID_2 (*(uint32_t*)0x1ffff7f0) + +#define USE_PIN_AF + +#ifndef AT32F4 +#define AT32F4 +#endif + +#define SET_BIT(REG, BIT) ((REG) |= (BIT)) +#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT)) +#define READ_BIT(REG, BIT) ((REG) & (BIT)) +#define CLEAR_REG(REG) ((REG) = (0x0)) +#define WRITE_REG(REG, VAL) ((REG) = (VAL)) +#define READ_REG(REG) ((REG)) +#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK))) + #elif defined(SIMULATOR_BUILD) // Nop +#undef USE_TIMER_AF #else #error "Invalid chipset specified. Update platform.h" diff --git a/src/main/startup/at32/at32f435_437.h b/src/main/startup/at32/at32f435_437.h new file mode 100644 index 0000000000..636169162f --- /dev/null +++ b/src/main/startup/at32/at32f435_437.h @@ -0,0 +1,779 @@ +/** + ************************************************************************** + * @file at32f435_437.h + * @version v2.0.4 + * @date 2021-12-31 + * @brief at32f435_437 header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#ifndef __AT32F435_437_H +#define __AT32F435_437_H + +#ifdef __cplusplus +extern "C" { +#endif + +#if defined (__CC_ARM) + #pragma anon_unions +#endif + + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup AT32F435_437 + * @{ + */ + +/** @addtogroup Library_configuration_section + * @{ + */ + +/** + * tip: to avoid modifying this file each time you need to switch between these + * devices, you can define the device in your toolchain compiler preprocessor. + */ + +#if !defined (AT32F435CCU7) && !defined (AT32F435CGU7) && !defined (AT32F435CMU7) && \ + !defined (AT32F435CCT7) && !defined (AT32F435CGT7) && !defined (AT32F435CMT7) && \ + !defined (AT32F435RCT7) && !defined (AT32F435RGT7) && !defined (AT32F435RMT7) && \ + !defined (AT32F435VCT7) && !defined (AT32F435VGT7) && !defined (AT32F435VMT7) && \ + !defined (AT32F435ZCT7) && !defined (AT32F435ZGT7) && !defined (AT32F435ZMT7) && \ + !defined (AT32F437RCT7) && !defined (AT32F437RGT7) && !defined (AT32F437RMT7) && \ + !defined (AT32F437VCT7) && !defined (AT32F437VGT7) && !defined (AT32F437VMT7) && \ + !defined (AT32F437ZCT7) && !defined (AT32F437ZGT7) && !defined (AT32F437ZMT7) + + #error "Please select first the target device used in your application (in at32f435_437.h file)" +#endif + +#if defined (AT32F435CCU7) || defined (AT32F435CGU7) || defined (AT32F435CMU7) || \ + defined (AT32F435CCT7) || defined (AT32F435CGT7) || defined (AT32F435CMT7) || \ + defined (AT32F435RCT7) || defined (AT32F435RGT7) || defined (AT32F435RMT7) || \ + defined (AT32F435VCT7) || defined (AT32F435VGT7) || defined (AT32F435VMT7) || \ + defined (AT32F435ZCT7) || defined (AT32F435ZGT7) || defined (AT32F435ZMT7) + + #define AT32F435xx +#endif + +#if defined (AT32F437RCT7) || defined (AT32F437RGT7) || defined (AT32F437RMT7) || \ + defined (AT32F437VCT7) || defined (AT32F437VGT7) || defined (AT32F437VMT7) || \ + defined (AT32F437ZCT7) || defined (AT32F437ZGT7) || defined (AT32F437ZMT7) + + #define AT32F437xx +#endif + +#ifndef USE_STDPERIPH_DRIVER +/** + * @brief comment the line below if you will not use the peripherals drivers. + * in this case, these drivers will not be included and the application code will + * be based on direct access to peripherals registers + */ + #ifdef _RTE_ + #include "RTE_Components.h" + #ifdef RTE_DEVICE_STDPERIPH_FRAMEWORK + #define USE_STDPERIPH_DRIVER + #endif + #endif +#endif + +/** + * @brief at32f435_437 standard peripheral library version number + */ +#define __AT32F435_437_LIBRARY_VERSION_MAJOR (0x02) /*!< [31:24] major version */ +#define __AT32F435_437_LIBRARY_VERSION_MIDDLE (0x00) /*!< [23:16] middle version */ +#define __AT32F435_437_LIBRARY_VERSION_MINOR (0x04) /*!< [15:8] minor version */ +#define __AT32F435_437_LIBRARY_VERSION_RC (0x00) /*!< [7:0] release candidate */ +#define __AT32F435_437_LIBRARY_VERSION ((__AT32F435_437_LIBRARY_VERSION_MAJOR << 24) | \ + (__AT32F435_437_LIBRARY_VERSION_MIDDLE << 16) | \ + (__AT32F435_437_LIBRARY_VERSION_MINOR << 8) | \ + (__AT32F435_437_LIBRARY_VERSION_RC)) + +/** + * @} + */ + +/** @addtogroup configuration_section_for_cmsis + * @{ + */ + +/** + * @brief configuration of the cortex-m4 processor and core peripherals + */ +#define __CM4_REV 0x0001U /*!< core revision r0p1 */ +#define __MPU_PRESENT 1 /*!< mpu present */ +#define __NVIC_PRIO_BITS 4 /*!< at32 uses 4 bits for the priority levels */ +#define __Vendor_SysTickConfig 0 /*!< set to 1 if different systick config is used */ +#define __FPU_PRESENT 1U /*!< fpu present */ + +/** + * @brief at32f435_437 interrupt number definition, according to the selected device + * in @ref library_configuration_section + */ +typedef enum IRQn +{ + /****** cortex-m4 processor exceptions numbers ***************************************************/ + Reset_IRQn = -15, /*!< 1 reset vector, invoked on power up and warm reset */ + NonMaskableInt_IRQn = -14, /*!< 2 non maskable interrupt */ + HardFault_IRQn = -13, /*!< 3 hard fault, all classes of fault */ + MemoryManagement_IRQn = -12, /*!< 4 cortex-m4 memory management interrupt */ + BusFault_IRQn = -11, /*!< 5 cortex-m4 bus fault interrupt */ + UsageFault_IRQn = -10, /*!< 6 cortex-m4 usage fault interrupt */ + SVCall_IRQn = -5, /*!< 11 cortex-m4 sv call interrupt */ + DebugMonitor_IRQn = -4, /*!< 12 cortex-m4 debug monitor interrupt */ + PendSV_IRQn = -2, /*!< 14 cortex-m4 pend sv interrupt */ + SysTick_IRQn = -1, /*!< 15 cortex-m4 system tick interrupt */ + + /****** at32 specific interrupt numbers *********************************************************/ + WWDT_IRQn = 0, /*!< window watchdog timer interrupt */ + PVM_IRQn = 1, /*!< pvm through exint line detection interrupt */ + TAMP_STAMP_IRQn = 2, /*!< tamper and timestamp interrupts through the exint line */ + ERTC_WKUP_IRQn = 3, /*!< ertc wakeup through the exint line */ + FLASH_IRQn = 4, /*!< flash global interrupt */ + CRM_IRQn = 5, /*!< crm global interrupt */ + EXINT0_IRQn = 6, /*!< exint line0 interrupt */ + EXINT1_IRQn = 7, /*!< exint line1 interrupt */ + EXINT2_IRQn = 8, /*!< exint line2 interrupt */ + EXINT3_IRQn = 9, /*!< exint line3 interrupt */ + EXINT4_IRQn = 10, /*!< exint line4 interrupt */ + EDMA_Stream1_IRQn = 11, /*!< edma stream 1 global interrupt */ + EDMA_Stream2_IRQn = 12, /*!< edma stream 2 global interrupt */ + EDMA_Stream3_IRQn = 13, /*!< edma stream 3 global interrupt */ + EDMA_Stream4_IRQn = 14, /*!< edma stream 4 global interrupt */ + EDMA_Stream5_IRQn = 15, /*!< edma stream 5 global interrupt */ + EDMA_Stream6_IRQn = 16, /*!< edma stream 6 global interrupt */ + EDMA_Stream7_IRQn = 17, /*!< edma stream 7 global interrupt */ + +#if defined (AT32F435xx) + ADC1_2_3_IRQn = 18, /*!< adc1 adc2 and adc3 global interrupt */ + CAN1_TX_IRQn = 19, /*!< can1 tx interrupts */ + CAN1_RX0_IRQn = 20, /*!< can1 rx0 interrupts */ + CAN1_RX1_IRQn = 21, /*!< can1 rx1 interrupt */ + CAN1_SE_IRQn = 22, /*!< can1 se interrupt */ + EXINT9_5_IRQn = 23, /*!< external line[9:5] interrupts */ + TMR1_BRK_TMR9_IRQn = 24, /*!< tmr1 brake interrupt */ + TMR1_OVF_TMR10_IRQn = 25, /*!< tmr1 overflow interrupt */ + TMR1_TRG_HALL_TMR11_IRQn = 26, /*!< tmr1 trigger and hall interrupt */ + TMR1_CH_IRQn = 27, /*!< tmr1 channel interrupt */ + TMR2_GLOBAL_IRQn = 28, /*!< tmr2 global interrupt */ + TMR3_GLOBAL_IRQn = 29, /*!< tmr3 global interrupt */ + TMR4_GLOBAL_IRQn = 30, /*!< tmr4 global interrupt */ + I2C1_EVT_IRQn = 31, /*!< i2c1 event interrupt */ + I2C1_ERR_IRQn = 32, /*!< i2c1 error interrupt */ + I2C2_EVT_IRQn = 33, /*!< i2c2 event interrupt */ + I2C2_ERR_IRQn = 34, /*!< i2c2 error interrupt */ + SPI1_IRQn = 35, /*!< spi1 global interrupt */ + SPI2_I2S2EXT_IRQn = 36, /*!< spi2 global interrupt */ + USART1_IRQn = 37, /*!< usart1 global interrupt */ + USART2_IRQn = 38, /*!< usart2 global interrupt */ + USART3_IRQn = 39, /*!< usart3 global interrupt */ + EXINT15_10_IRQn = 40, /*!< external line[15:10] interrupts */ + ERTCAlarm_IRQn = 41, /*!< ertc alarm through exint line interrupt */ + OTGFS1_WKUP_IRQn = 42, /*!< otgfs1 wakeup from suspend through exint line interrupt */ + TMR8_BRK_TMR12_IRQn = 43, /*!< tmr8 brake interrupt */ + TMR8_OVF_TMR13_IRQn = 44, /*!< tmr8 overflow interrupt */ + TMR8_TRG_HALL_TMR14_IRQn = 45, /*!< tmr8 trigger and hall interrupt */ + TMR8_CH_IRQn = 46, /*!< tmr8 channel interrupt */ + EDMA_Stream8_IRQn = 47, /*!< edma stream 8 global interrupt */ + XMC_IRQn = 48, /*!< xmc global interrupt */ + SDIO1_IRQn = 49, /*!< sdio global interrupt */ + TMR5_GLOBAL_IRQn = 50, /*!< tmr5 global interrupt */ + SPI3_I2S3EXT_IRQn = 51, /*!< spi3 global interrupt */ + UART4_IRQn = 52, /*!< uart4 global interrupt */ + UART5_IRQn = 53, /*!< uart5 global interrupt */ + TMR6_DAC_GLOBAL_IRQn = 54, /*!< tmr6 and dac global interrupt */ + TMR7_GLOBAL_IRQn = 55, /*!< tmr7 global interrupt */ + DMA1_Channel1_IRQn = 56, /*!< dma1 channel 0 global interrupt */ + DMA1_Channel2_IRQn = 57, /*!< dma1 channel 1 global interrupt */ + DMA1_Channel3_IRQn = 58, /*!< dma1 channel 2 global interrupt */ + DMA1_Channel4_IRQn = 59, /*!< dma1 channel 3 global interrupt */ + DMA1_Channel5_IRQn = 60, /*!< dma1 channel 4 global interrupt */ + CAN2_TX_IRQn = 63, /*!< can2 tx interrupt */ + CAN2_RX0_IRQn = 64, /*!< can2 rx0 interrupt */ + CAN2_RX1_IRQn = 65, /*!< can2 rx1 interrupt */ + CAN2_SE_IRQn = 66, /*!< can2 se interrupt */ + OTGFS1_IRQn = 67, /*!< otgfs1 interrupt */ + DMA1_Channel6_IRQn = 68, /*!< dma1 channel 5 global interrupt */ + DMA1_Channel7_IRQn = 69, /*!< dma1 channel 6 global interrupt */ + USART6_IRQn = 71, /*!< usart6 interrupt */ + I2C3_EVT_IRQn = 72, /*!< i2c3 event interrupt */ + I2C3_ERR_IRQn = 73, /*!< i2c3 error interrupt */ + OTGFS2_WKUP_IRQn = 76, /*!< otgfs2 wakeup from suspend through exint line interrupt */ + OTGFS2_IRQn = 77, /*!< otgfs2 interrupt */ + DVP_IRQn = 78, /*!< dvp interrupt */ + FPU_IRQn = 81, /*!< fpu interrupt */ + UART7_IRQn = 82, /*!< uart7 interrupt */ + UART8_IRQn = 83, /*!< uart8 interrupt */ + SPI4_IRQn = 84, /*!< spi4 global interrupt */ + QSPI2_IRQn = 91, /*!< qspi2 global interrupt */ + QSPI1_IRQn = 92, /*!< qspi1 global interrupt */ + DMAMUX_IRQn = 94, /*!< dmamux global interrupt */ + SDIO2_IRQn = 102, /*!< sdio2 global interrupt */ + ACC_IRQn = 103, /*!< acc interrupt */ + TMR20_BRK_IRQn = 104, /*!< tmr20 brake interrupt */ + TMR20_OVF_IRQn = 105, /*!< tmr20 overflow interrupt */ + TMR20_TRG_HALL_IRQn = 106, /*!< tmr20 trigger and hall interrupt */ + TMR20_CH_IRQn = 107, /*!< tmr20 channel interrupt */ + DMA2_Channel1_IRQn = 108, /*!< dma1 channel 1 global interrupt */ + DMA2_Channel2_IRQn = 109, /*!< dma1 channel 2 global interrupt */ + DMA2_Channel3_IRQn = 110, /*!< dma1 channel 3 global interrupt */ + DMA2_Channel4_IRQn = 111, /*!< dma1 channel 4 global interrupt */ + DMA2_Channel5_IRQn = 112, /*!< dma1 channel 5 global interrupt */ + DMA2_Channel6_IRQn = 113, /*!< dma1 channel 6 global interrupt */ + DMA2_Channel7_IRQn = 114, /*!< dma1 channel 7 global interrupt */ +#endif + +#if defined (AT32F437xx) + ADC1_2_3_IRQn = 18, /*!< adc1 adc2 and adc3 global interrupt */ + CAN1_TX_IRQn = 19, /*!< can1 tx interrupts */ + CAN1_RX0_IRQn = 20, /*!< can1 rx0 interrupts */ + CAN1_RX1_IRQn = 21, /*!< can1 rx1 interrupt */ + CAN1_SE_IRQn = 22, /*!< can1 se interrupt */ + EXINT9_5_IRQn = 23, /*!< external line[9:5] interrupts */ + TMR1_BRK_TMR9_IRQn = 24, /*!< tmr1 brake interrupt */ + TMR1_OVF_TMR10_IRQn = 25, /*!< tmr1 overflow interrupt */ + TMR1_TRG_HALL_TMR11_IRQn = 26, /*!< tmr1 trigger and hall interrupt */ + TMR1_CH_IRQn = 27, /*!< tmr1 channel interrupt */ + TMR2_GLOBAL_IRQn = 28, /*!< tmr2 global interrupt */ + TMR3_GLOBAL_IRQn = 29, /*!< tmr3 global interrupt */ + TMR4_GLOBAL_IRQn = 30, /*!< tmr4 global interrupt */ + I2C1_EVT_IRQn = 31, /*!< i2c1 event interrupt */ + I2C1_ERR_IRQn = 32, /*!< i2c1 error interrupt */ + I2C2_EVT_IRQn = 33, /*!< i2c2 event interrupt */ + I2C2_ERR_IRQn = 34, /*!< i2c2 error interrupt */ + SPI1_IRQn = 35, /*!< spi1 global interrupt */ + SPI2_I2S2EXT_IRQn = 36, /*!< spi2 global interrupt */ + USART1_IRQn = 37, /*!< usart1 global interrupt */ + USART2_IRQn = 38, /*!< usart2 global interrupt */ + USART3_IRQn = 39, /*!< usart3 global interrupt */ + EXINT15_10_IRQn = 40, /*!< external line[15:10] interrupts */ + ERTCAlarm_IRQn = 41, /*!< ertc alarm through exint line interrupt */ + OTGFS1_WKUP_IRQn = 42, /*!< otgfs1 wakeup from suspend through exint line interrupt */ + TMR8_BRK_TMR12_IRQn = 43, /*!< tmr8 brake interrupt */ + TMR8_OVF_TMR13_IRQn = 44, /*!< tmr8 overflow interrupt */ + TMR8_TRG_HALL_TMR14_IRQn = 45, /*!< tmr8 trigger and hall interrupt */ + TMR8_CH_IRQn = 46, /*!< tmr8 channel interrupt */ + EDMA_Stream8_IRQn = 47, /*!< dma1 stream 8 global interrupt */ + XMC_IRQn = 48, /*!< xmc global interrupt */ + SDIO1_IRQn = 49, /*!< sdio global interrupt */ + TMR5_GLOBAL_IRQn = 50, /*!< tmr5 global interrupt */ + SPI3_I2S3EXT_IRQn = 51, /*!< spi3 global interrupt */ + UART4_IRQn = 52, /*!< uart4 global interrupt */ + UART5_IRQn = 53, /*!< uart5 global interrupt */ + TMR6_DAC_GLOBAL_IRQn = 54, /*!< tmr6 and dac global interrupt */ + TMR7_GLOBAL_IRQn = 55, /*!< tmr7 global interrupt */ + DMA1_Channel1_IRQn = 56, /*!< dma1 channel 0 global interrupt */ + DMA1_Channel2_IRQn = 57, /*!< dma1 channel 1 global interrupt */ + DMA1_Channel3_IRQn = 58, /*!< dma1 channel 2 global interrupt */ + DMA1_Channel4_IRQn = 59, /*!< dma1 channel 3 global interrupt */ + DMA1_Channel5_IRQn = 60, /*!< dma1 channel 4 global interrupt */ + EMAC_IRQn = 61, /*!< emac interrupt */ + EMAC_WKUP_IRQn = 62, /*!< emac wakeup interrupt */ + CAN2_TX_IRQn = 63, /*!< can2 tx interrupt */ + CAN2_RX0_IRQn = 64, /*!< can2 rx0 interrupt */ + CAN2_RX1_IRQn = 65, /*!< can2 rx1 interrupt */ + CAN2_SE_IRQn = 66, /*!< can2 se interrupt */ + OTGFS1_IRQn = 67, /*!< otgfs1 interrupt */ + DMA1_Channel6_IRQn = 68, /*!< dma1 channel 5 global interrupt */ + DMA1_Channel7_IRQn = 69, /*!< dma1 channel 6 global interrupt */ + USART6_IRQn = 71, /*!< usart6 interrupt */ + I2C3_EVT_IRQn = 72, /*!< i2c3 event interrupt */ + I2C3_ERR_IRQn = 73, /*!< i2c3 error interrupt */ + OTGFS2_WKUP_IRQn = 76, /*!< otgfs2 wakeup from suspend through exint line interrupt */ + OTGFS2_IRQn = 77, /*!< otgfs2 interrupt */ + DVP_IRQn = 78, /*!< dvp interrupt */ + FPU_IRQn = 81, /*!< fpu interrupt */ + UART7_IRQn = 82, /*!< uart7 interrupt */ + UART8_IRQn = 83, /*!< uart8 interrupt */ + SPI4_IRQn = 84, /*!< spi4 global interrupt */ + QSPI2_IRQn = 91, /*!< qspi2 global interrupt */ + QSPI1_IRQn = 92, /*!< qspi1 global interrupt */ + DMAMUX_IRQn = 94, /*!< dmamux global interrupt */ + SDIO2_IRQn = 102, /*!< sdio2 global interrupt */ + ACC_IRQn = 103, /*!< acc interrupt */ + TMR20_BRK_IRQn = 104, /*!< tmr20 brake interrupt */ + TMR20_OVF_IRQn = 105, /*!< tmr20 overflow interrupt */ + TMR20_TRG_HALL_IRQn = 106, /*!< tmr20 trigger and hall interrupt */ + TMR20_CH_IRQn = 107, /*!< tmr20 channel interrupt */ + DMA2_Channel1_IRQn = 108, /*!< dma1 channel 1 global interrupt */ + DMA2_Channel2_IRQn = 109, /*!< dma1 channel 2 global interrupt */ + DMA2_Channel3_IRQn = 110, /*!< dma1 channel 3 global interrupt */ + DMA2_Channel4_IRQn = 111, /*!< dma1 channel 4 global interrupt */ + DMA2_Channel5_IRQn = 112, /*!< dma1 channel 5 global interrupt */ + DMA2_Channel6_IRQn = 113, /*!< dma1 channel 6 global interrupt */ + DMA2_Channel7_IRQn = 114, /*!< dma1 channel 7 global interrupt */ +#endif + +} IRQn_Type; + +/** + * @} + */ + +#include "core_cm4.h" +#include "system_at32f435_437.h" +#include + +/** @addtogroup Exported_types + * @{ + */ + +typedef int32_t INT32; +typedef int16_t INT16; +typedef int8_t INT8; +typedef uint32_t UINT32; +typedef uint16_t UINT16; +typedef uint8_t UINT8; + +typedef int32_t s32; +typedef int16_t s16; +typedef int8_t s8; + +typedef const int32_t sc32; /*!< read only */ +typedef const int16_t sc16; /*!< read only */ +typedef const int8_t sc8; /*!< read only */ + +typedef __IO int32_t vs32; +typedef __IO int16_t vs16; +typedef __IO int8_t vs8; + +typedef __I int32_t vsc32; /*!< read only */ +typedef __I int16_t vsc16; /*!< read only */ +typedef __I int8_t vsc8; /*!< read only */ + +typedef uint32_t u32; +typedef uint16_t u16; +typedef uint8_t u8; + +typedef const uint32_t uc32; /*!< read only */ +typedef const uint16_t uc16; /*!< read only */ +typedef const uint8_t uc8; /*!< read only */ + +typedef __IO uint32_t vu32; +typedef __IO uint16_t vu16; +typedef __IO uint8_t vu8; + +typedef __I uint32_t vuc32; /*!< read only */ +typedef __I uint16_t vuc16; /*!< read only */ +typedef __I uint8_t vuc8; /*!< read only */ + +typedef enum {RESET = 0, SET = !RESET} flag_status; +typedef enum {FALSE = 0, TRUE = !FALSE} confirm_state; +typedef enum {ERROR = 0, SUCCESS = !ERROR} error_status; + +/** + * @} + */ + +/** @addtogroup Exported_macro + * @{ + */ + +#define REG8(addr) *(volatile uint8_t *)(addr) +#define REG16(addr) *(volatile uint16_t *)(addr) +#define REG32(addr) *(volatile uint32_t *)(addr) + +#define MAKE_VALUE(reg_offset, bit_num) (((reg_offset) << 16) | (bit_num & 0x1f)) + +#define PERIPH_REG(periph_base, value) REG32((periph_base + (value >> 16))) +#define PERIPH_REG_BIT(value) (0x1u << (value & 0x1f)) + +/** + * @} + */ + +/** @addtogroup Peripheral_memory_map + * @{ + */ + +#define XMC_SDRAM_MEM_BASE ((uint32_t)0xC0000000) +#define QSPI2_MEM_BASE ((uint32_t)0xB0000000) +#define XMC_CARD_MEM_BASE ((uint32_t)0xA8000000) +#define QSPI2_REG_BASE ((uint32_t)0xA0002000) +#define QSPI1_REG_BASE ((uint32_t)0xA0001000) +#define XMC_REG_BASE ((uint32_t)0xA0000000) +#define XMC_BANK1_REG_BASE (XMC_REG_BASE + 0x0000) +#define XMC_BANK2_REG_BASE (XMC_REG_BASE + 0x0060) +#define XMC_BANK3_REG_BASE (XMC_REG_BASE + 0x0080) +#define XMC_BANK4_REG_BASE (XMC_REG_BASE + 0x00A0) +#define XMC_SDRAM_REG_BASE (XMC_REG_BASE + 0x0140) +#define QSPI1_MEM_BASE ((uint32_t)0x90000000) +#define XMC_MEM_BASE ((uint32_t)0x60000000) +#define PERIPH_BASE ((uint32_t)0x40000000) +#define SRAM_BB_BASE ((uint32_t)0x22000000) +#define PERIPH_BB_BASE ((uint32_t)0x42000000) +#define SRAM_BASE ((uint32_t)0x20000000) +#define USD_BASE ((uint32_t)0x1FFFC000) +#define FLASH_BASE ((uint32_t)0x08000000) + +#define DEBUG_BASE ((uint32_t)0xE0042000) + +#define APB1PERIPH_BASE (PERIPH_BASE) +#define APB2PERIPH_BASE (PERIPH_BASE + 0x10000) +#define AHBPERIPH1_BASE (PERIPH_BASE + 0x20000) +#define AHBPERIPH2_BASE (PERIPH_BASE + 0x10000000) + +#if defined (AT32F435xx) +/* apb1 bus base address */ +#define UART8_BASE (APB1PERIPH_BASE + 0x7C00) +#define UART7_BASE (APB1PERIPH_BASE + 0x7800) +#define DAC_BASE (APB1PERIPH_BASE + 0x7400) +#define PWC_BASE (APB1PERIPH_BASE + 0x7000) +#define CAN2_BASE (APB1PERIPH_BASE + 0x6800) +#define CAN1_BASE (APB1PERIPH_BASE + 0x6400) +#define I2C3_BASE (APB1PERIPH_BASE + 0x5C00) +#define I2C2_BASE (APB1PERIPH_BASE + 0x5800) +#define I2C1_BASE (APB1PERIPH_BASE + 0x5400) +#define UART5_BASE (APB1PERIPH_BASE + 0x5000) +#define UART4_BASE (APB1PERIPH_BASE + 0x4C00) +#define USART3_BASE (APB1PERIPH_BASE + 0x4800) +#define USART2_BASE (APB1PERIPH_BASE + 0x4400) +#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00) +#define SPI2_BASE (APB1PERIPH_BASE + 0x3800) +#define WDT_BASE (APB1PERIPH_BASE + 0x3000) +#define WWDT_BASE (APB1PERIPH_BASE + 0x2C00) +#define ERTC_BASE (APB1PERIPH_BASE + 0x2800) +#define TMR14_BASE (APB1PERIPH_BASE + 0x2000) +#define TMR13_BASE (APB1PERIPH_BASE + 0x1C00) +#define TMR12_BASE (APB1PERIPH_BASE + 0x1800) +#define TMR7_BASE (APB1PERIPH_BASE + 0x1400) +#define TMR6_BASE (APB1PERIPH_BASE + 0x1000) +#define TMR5_BASE (APB1PERIPH_BASE + 0x0C00) +#define TMR4_BASE (APB1PERIPH_BASE + 0x0800) +#define TMR3_BASE (APB1PERIPH_BASE + 0x0400) +#define TMR2_BASE (APB1PERIPH_BASE + 0x0000) +/* apb2 bus base address */ +#define I2S2EXT_BASE (APB2PERIPH_BASE + 0x7800) +#define I2S3EXT_BASE (APB2PERIPH_BASE + 0x7C00) +#define ACC_BASE (APB2PERIPH_BASE + 0x7400) +#define TMR20_BASE (APB2PERIPH_BASE + 0x4C00) +#define TMR11_BASE (APB2PERIPH_BASE + 0x4800) +#define TMR10_BASE (APB2PERIPH_BASE + 0x4400) +#define TMR9_BASE (APB2PERIPH_BASE + 0x4000) +#define EXINT_BASE (APB2PERIPH_BASE + 0x3C00) +#define SCFG_BASE (APB2PERIPH_BASE + 0x3800) +#define SPI4_BASE (APB2PERIPH_BASE + 0x3400) +#define SPI1_BASE (APB2PERIPH_BASE + 0x3000) +#define ADC1_BASE (APB2PERIPH_BASE + 0x2000) +#define ADC2_BASE (APB2PERIPH_BASE + 0x2100) +#define ADC3_BASE (APB2PERIPH_BASE + 0x2200) +#define ADCCOM_BASE (APB2PERIPH_BASE + 0x2300) +#define USART6_BASE (APB2PERIPH_BASE + 0x1400) +#define USART1_BASE (APB2PERIPH_BASE + 0x1000) +#define TMR8_BASE (APB2PERIPH_BASE + 0x0400) +#define TMR1_BASE (APB2PERIPH_BASE + 0x0000) +/* ahb bus base address */ +#define OTGFS2_BASE (AHBPERIPH1_BASE + 0x20000) +#define SDIO1_BASE (AHBPERIPH1_BASE + 0xC400) +#define GPIOH_BASE (AHBPERIPH1_BASE + 0x1C00) +#define GPIOG_BASE (AHBPERIPH1_BASE + 0x1800) +#define GPIOF_BASE (AHBPERIPH1_BASE + 0x1400) +#define GPIOE_BASE (AHBPERIPH1_BASE + 0x1000) +#define GPIOD_BASE (AHBPERIPH1_BASE + 0x0C00) +#define GPIOC_BASE (AHBPERIPH1_BASE + 0x0800) +#define GPIOB_BASE (AHBPERIPH1_BASE + 0x0400) +#define GPIOA_BASE (AHBPERIPH1_BASE + 0x0000) + +#define DMA1_BASE (AHBPERIPH1_BASE + 0x6400) +#define DMA1_CHANNEL1_BASE (DMA1_BASE + 0x0008) +#define DMA1_CHANNEL2_BASE (DMA1_BASE + 0x001C) +#define DMA1_CHANNEL3_BASE (DMA1_BASE + 0x0030) +#define DMA1_CHANNEL4_BASE (DMA1_BASE + 0x0044) +#define DMA1_CHANNEL5_BASE (DMA1_BASE + 0x0058) +#define DMA1_CHANNEL6_BASE (DMA1_BASE + 0x006C) +#define DMA1_CHANNEL7_BASE (DMA1_BASE + 0x0080) + +#define DMA1MUX_BASE (DMA1_BASE + 0x0104) +#define DMA1MUX_CHANNEL1_BASE (DMA1MUX_BASE) +#define DMA1MUX_CHANNEL2_BASE (DMA1MUX_BASE + 0x0004) +#define DMA1MUX_CHANNEL3_BASE (DMA1MUX_BASE + 0x0008) +#define DMA1MUX_CHANNEL4_BASE (DMA1MUX_BASE + 0x000C) +#define DMA1MUX_CHANNEL5_BASE (DMA1MUX_BASE + 0x0010) +#define DMA1MUX_CHANNEL6_BASE (DMA1MUX_BASE + 0x0014) +#define DMA1MUX_CHANNEL7_BASE (DMA1MUX_BASE + 0x0018) + +#define DMA1MUX_GENERATOR1_BASE (DMA1_BASE + 0x0120) +#define DMA1MUX_GENERATOR2_BASE (DMA1_BASE + 0x0124) +#define DMA1MUX_GENERATOR3_BASE (DMA1_BASE + 0x0128) +#define DMA1MUX_GENERATOR4_BASE (DMA1_BASE + 0x012C) + +#define DMA2_BASE (AHBPERIPH1_BASE + 0x6600) +#define DMA2_CHANNEL1_BASE (DMA2_BASE + 0x0008) +#define DMA2_CHANNEL2_BASE (DMA2_BASE + 0x001C) +#define DMA2_CHANNEL3_BASE (DMA2_BASE + 0x0030) +#define DMA2_CHANNEL4_BASE (DMA2_BASE + 0x0044) +#define DMA2_CHANNEL5_BASE (DMA2_BASE + 0x0058) +#define DMA2_CHANNEL6_BASE (DMA2_BASE + 0x006C) +#define DMA2_CHANNEL7_BASE (DMA2_BASE + 0x0080) + +#define DMA2MUX_BASE (DMA2_BASE + 0x0104) +#define DMA2MUX_CHANNEL1_BASE (DMA2MUX_BASE) +#define DMA2MUX_CHANNEL2_BASE (DMA2MUX_BASE + 0x0004) +#define DMA2MUX_CHANNEL3_BASE (DMA2MUX_BASE + 0x0008) +#define DMA2MUX_CHANNEL4_BASE (DMA2MUX_BASE + 0x000C) +#define DMA2MUX_CHANNEL5_BASE (DMA2MUX_BASE + 0x0010) +#define DMA2MUX_CHANNEL6_BASE (DMA2MUX_BASE + 0x0014) +#define DMA2MUX_CHANNEL7_BASE (DMA2MUX_BASE + 0x0018) + +#define DMA2MUX_GENERATOR1_BASE (DMA2_BASE + 0x0120) +#define DMA2MUX_GENERATOR2_BASE (DMA2_BASE + 0x0124) +#define DMA2MUX_GENERATOR3_BASE (DMA2_BASE + 0x0128) +#define DMA2MUX_GENERATOR4_BASE (DMA2_BASE + 0x012C) + +#define EDMA_BASE (AHBPERIPH1_BASE + 0x6000) +#define EDMA_STREAM1_BASE (EDMA_BASE + 0x0010) +#define EDMA_STREAM2_BASE (EDMA_BASE + 0x0028) +#define EDMA_STREAM3_BASE (EDMA_BASE + 0x0040) +#define EDMA_STREAM4_BASE (EDMA_BASE + 0x0058) +#define EDMA_STREAM5_BASE (EDMA_BASE + 0x0070) +#define EDMA_STREAM6_BASE (EDMA_BASE + 0x0088) +#define EDMA_STREAM7_BASE (EDMA_BASE + 0x00A0) +#define EDMA_STREAM8_BASE (EDMA_BASE + 0x00B8) + +#define EDMA_2D_BASE (EDMA_BASE + 0x00F4) +#define EDMA_STREAM1_2D_BASE (EDMA_2D_BASE + 0x0004) +#define EDMA_STREAM2_2D_BASE (EDMA_2D_BASE + 0x000C) +#define EDMA_STREAM3_2D_BASE (EDMA_2D_BASE + 0x0014) +#define EDMA_STREAM4_2D_BASE (EDMA_2D_BASE + 0x001C) +#define EDMA_STREAM5_2D_BASE (EDMA_2D_BASE + 0x0024) +#define EDMA_STREAM6_2D_BASE (EDMA_2D_BASE + 0x002C) +#define EDMA_STREAM7_2D_BASE (EDMA_2D_BASE + 0x0034) +#define EDMA_STREAM8_2D_BASE (EDMA_2D_BASE + 0x003C) + +#define EDMA_LL_BASE (EDMA_BASE + 0x00D0) +#define EDMA_STREAM1_LL_BASE (EDMA_LL_BASE + 0x0004) +#define EDMA_STREAM2_LL_BASE (EDMA_LL_BASE + 0x0008) +#define EDMA_STREAM3_LL_BASE (EDMA_LL_BASE + 0x000C) +#define EDMA_STREAM4_LL_BASE (EDMA_LL_BASE + 0x0010) +#define EDMA_STREAM5_LL_BASE (EDMA_LL_BASE + 0x0014) +#define EDMA_STREAM6_LL_BASE (EDMA_LL_BASE + 0x0018) +#define EDMA_STREAM7_LL_BASE (EDMA_LL_BASE + 0x001C) +#define EDMA_STREAM8_LL_BASE (EDMA_LL_BASE + 0x0020) + +#define EDMAMUX_BASE (EDMA_BASE + 0x0140) +#define EDMAMUX_CHANNEL1_BASE (EDMAMUX_BASE) +#define EDMAMUX_CHANNEL2_BASE (EDMAMUX_BASE + 0x0004) +#define EDMAMUX_CHANNEL3_BASE (EDMAMUX_BASE + 0x0008) +#define EDMAMUX_CHANNEL4_BASE (EDMAMUX_BASE + 0x000C) +#define EDMAMUX_CHANNEL5_BASE (EDMAMUX_BASE + 0x0010) +#define EDMAMUX_CHANNEL6_BASE (EDMAMUX_BASE + 0x0014) +#define EDMAMUX_CHANNEL7_BASE (EDMAMUX_BASE + 0x0018) +#define EDMAMUX_CHANNEL8_BASE (EDMAMUX_BASE + 0x001C) + +#define EDMAMUX_GENERATOR1_BASE (EDMA_BASE + 0x0160) +#define EDMAMUX_GENERATOR2_BASE (EDMA_BASE + 0x0164) +#define EDMAMUX_GENERATOR3_BASE (EDMA_BASE + 0x0168) +#define EDMAMUX_GENERATOR4_BASE (EDMA_BASE + 0x016C) + +#define FLASH_REG_BASE (AHBPERIPH1_BASE + 0x3C00) +#define CRM_BASE (AHBPERIPH1_BASE + 0x3800) +#define CRC_BASE (AHBPERIPH1_BASE + 0x3000) +#define SDIO2_BASE (AHBPERIPH2_BASE + 0x61000) +#define DVP_BASE (AHBPERIPH2_BASE + 0x50000) +#define OTGFS1_BASE (AHBPERIPH2_BASE + 0x00000) +#endif + +#if defined (AT32F437xx) +/* apb1 bus base address */ +#define UART8_BASE (APB1PERIPH_BASE + 0x7C00) +#define UART7_BASE (APB1PERIPH_BASE + 0x7800) +#define DAC_BASE (APB1PERIPH_BASE + 0x7400) +#define PWC_BASE (APB1PERIPH_BASE + 0x7000) +#define CAN2_BASE (APB1PERIPH_BASE + 0x6800) +#define CAN1_BASE (APB1PERIPH_BASE + 0x6400) +#define I2C3_BASE (APB1PERIPH_BASE + 0x5C00) +#define I2C2_BASE (APB1PERIPH_BASE + 0x5800) +#define I2C1_BASE (APB1PERIPH_BASE + 0x5400) +#define UART5_BASE (APB1PERIPH_BASE + 0x5000) +#define UART4_BASE (APB1PERIPH_BASE + 0x4C00) +#define USART3_BASE (APB1PERIPH_BASE + 0x4800) +#define USART2_BASE (APB1PERIPH_BASE + 0x4400) +#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00) +#define SPI2_BASE (APB1PERIPH_BASE + 0x3800) +#define WDT_BASE (APB1PERIPH_BASE + 0x3000) +#define WWDT_BASE (APB1PERIPH_BASE + 0x2C00) +#define ERTC_BASE (APB1PERIPH_BASE + 0x2800) +#define TMR14_BASE (APB1PERIPH_BASE + 0x2000) +#define TMR13_BASE (APB1PERIPH_BASE + 0x1C00) +#define TMR12_BASE (APB1PERIPH_BASE + 0x1800) +#define TMR7_BASE (APB1PERIPH_BASE + 0x1400) +#define TMR6_BASE (APB1PERIPH_BASE + 0x1000) +#define TMR5_BASE (APB1PERIPH_BASE + 0x0C00) +#define TMR4_BASE (APB1PERIPH_BASE + 0x0800) +#define TMR3_BASE (APB1PERIPH_BASE + 0x0400) +#define TMR2_BASE (APB1PERIPH_BASE + 0x0000) +/* apb2 bus base address */ +#define I2S2EXT_BASE (APB2PERIPH_BASE + 0x7800) +#define I2S3EXT_BASE (APB2PERIPH_BASE + 0x7C00) +#define ACC_BASE (APB2PERIPH_BASE + 0x7400) +#define TMR20_BASE (APB2PERIPH_BASE + 0x4C00) +#define TMR11_BASE (APB2PERIPH_BASE + 0x4800) +#define TMR10_BASE (APB2PERIPH_BASE + 0x4400) +#define TMR9_BASE (APB2PERIPH_BASE + 0x4000) +#define EXINT_BASE (APB2PERIPH_BASE + 0x3C00) +#define SCFG_BASE (APB2PERIPH_BASE + 0x3800) +#define SPI4_BASE (APB2PERIPH_BASE + 0x3400) +#define SPI1_BASE (APB2PERIPH_BASE + 0x3000) +#define ADC1_BASE (APB2PERIPH_BASE + 0x2000) +#define ADC2_BASE (APB2PERIPH_BASE + 0x2100) +#define ADC3_BASE (APB2PERIPH_BASE + 0x2200) +#define ADCCOM_BASE (APB2PERIPH_BASE + 0x2300) +#define USART6_BASE (APB2PERIPH_BASE + 0x1400) +#define USART1_BASE (APB2PERIPH_BASE + 0x1000) +#define TMR8_BASE (APB2PERIPH_BASE + 0x0400) +#define TMR1_BASE (APB2PERIPH_BASE + 0x0000) +/* ahb bus base address */ +#define OTGFS2_BASE (AHBPERIPH1_BASE + 0x20000) +#define SDIO1_BASE (AHBPERIPH1_BASE + 0xC400) +#define EMAC_BASE (AHBPERIPH1_BASE + 0x8000) +#define GPIOH_BASE (AHBPERIPH1_BASE + 0x1C00) +#define GPIOG_BASE (AHBPERIPH1_BASE + 0x1800) +#define GPIOF_BASE (AHBPERIPH1_BASE + 0x1400) +#define GPIOE_BASE (AHBPERIPH1_BASE + 0x1000) +#define GPIOD_BASE (AHBPERIPH1_BASE + 0x0C00) +#define GPIOC_BASE (AHBPERIPH1_BASE + 0x0800) +#define GPIOB_BASE (AHBPERIPH1_BASE + 0x0400) +#define GPIOA_BASE (AHBPERIPH1_BASE + 0x0000) + +#define DMA1_BASE (AHBPERIPH1_BASE + 0x6400) +#define DMA1_CHANNEL1_BASE (DMA1_BASE + 0x0008) +#define DMA1_CHANNEL2_BASE (DMA1_BASE + 0x001C) +#define DMA1_CHANNEL3_BASE (DMA1_BASE + 0x0030) +#define DMA1_CHANNEL4_BASE (DMA1_BASE + 0x0044) +#define DMA1_CHANNEL5_BASE (DMA1_BASE + 0x0058) +#define DMA1_CHANNEL6_BASE (DMA1_BASE + 0x006C) +#define DMA1_CHANNEL7_BASE (DMA1_BASE + 0x0080) + +#define DMA1MUX_BASE (DMA1_BASE + 0x0104) +#define DMA1MUX_CHANNEL1_BASE (DMA1MUX_BASE) +#define DMA1MUX_CHANNEL2_BASE (DMA1MUX_BASE + 0x0004) +#define DMA1MUX_CHANNEL3_BASE (DMA1MUX_BASE + 0x0008) +#define DMA1MUX_CHANNEL4_BASE (DMA1MUX_BASE + 0x000C) +#define DMA1MUX_CHANNEL5_BASE (DMA1MUX_BASE + 0x0010) +#define DMA1MUX_CHANNEL6_BASE (DMA1MUX_BASE + 0x0014) +#define DMA1MUX_CHANNEL7_BASE (DMA1MUX_BASE + 0x0018) + +#define DMA1MUX_GENERATOR1_BASE (DMA1_BASE + 0x0120) +#define DMA1MUX_GENERATOR2_BASE (DMA1_BASE + 0x0124) +#define DMA1MUX_GENERATOR3_BASE (DMA1_BASE + 0x0128) +#define DMA1MUX_GENERATOR4_BASE (DMA1_BASE + 0x012C) + +#define DMA2_BASE (AHBPERIPH1_BASE + 0x6600) +#define DMA2_CHANNEL1_BASE (DMA2_BASE + 0x0008) +#define DMA2_CHANNEL2_BASE (DMA2_BASE + 0x001C) +#define DMA2_CHANNEL3_BASE (DMA2_BASE + 0x0030) +#define DMA2_CHANNEL4_BASE (DMA2_BASE + 0x0044) +#define DMA2_CHANNEL5_BASE (DMA2_BASE + 0x0058) +#define DMA2_CHANNEL6_BASE (DMA2_BASE + 0x006C) +#define DMA2_CHANNEL7_BASE (DMA2_BASE + 0x0080) + +#define DMA2MUX_BASE (DMA2_BASE + 0x0104) +#define DMA2MUX_CHANNEL1_BASE (DMA2MUX_BASE) +#define DMA2MUX_CHANNEL2_BASE (DMA2MUX_BASE + 0x0004) +#define DMA2MUX_CHANNEL3_BASE (DMA2MUX_BASE + 0x0008) +#define DMA2MUX_CHANNEL4_BASE (DMA2MUX_BASE + 0x000C) +#define DMA2MUX_CHANNEL5_BASE (DMA2MUX_BASE + 0x0010) +#define DMA2MUX_CHANNEL6_BASE (DMA2MUX_BASE + 0x0014) +#define DMA2MUX_CHANNEL7_BASE (DMA2MUX_BASE + 0x0018) + +#define DMA2MUX_GENERATOR1_BASE (DMA2_BASE + 0x0120) +#define DMA2MUX_GENERATOR2_BASE (DMA2_BASE + 0x0124) +#define DMA2MUX_GENERATOR3_BASE (DMA2_BASE + 0x0128) +#define DMA2MUX_GENERATOR4_BASE (DMA2_BASE + 0x012C) + +#define EDMA_BASE (AHBPERIPH1_BASE + 0x6000) +#define EDMA_STREAM1_BASE (EDMA_BASE + 0x0010) +#define EDMA_STREAM2_BASE (EDMA_BASE + 0x0028) +#define EDMA_STREAM3_BASE (EDMA_BASE + 0x0040) +#define EDMA_STREAM4_BASE (EDMA_BASE + 0x0058) +#define EDMA_STREAM5_BASE (EDMA_BASE + 0x0070) +#define EDMA_STREAM6_BASE (EDMA_BASE + 0x0088) +#define EDMA_STREAM7_BASE (EDMA_BASE + 0x00A0) +#define EDMA_STREAM8_BASE (EDMA_BASE + 0x00B8) + +#define EDMA_2D_BASE (EDMA_BASE + 0x00F4) +#define EDMA_STREAM1_2D_BASE (EDMA_2D_BASE + 0x0004) +#define EDMA_STREAM2_2D_BASE (EDMA_2D_BASE + 0x000C) +#define EDMA_STREAM3_2D_BASE (EDMA_2D_BASE + 0x0014) +#define EDMA_STREAM4_2D_BASE (EDMA_2D_BASE + 0x001C) +#define EDMA_STREAM5_2D_BASE (EDMA_2D_BASE + 0x0024) +#define EDMA_STREAM6_2D_BASE (EDMA_2D_BASE + 0x002C) +#define EDMA_STREAM7_2D_BASE (EDMA_2D_BASE + 0x0034) +#define EDMA_STREAM8_2D_BASE (EDMA_2D_BASE + 0x003C) + +#define EDMA_LL_BASE (EDMA_BASE + 0x00D0) +#define EDMA_STREAM1_LL_BASE (EDMA_LL_BASE + 0x0004) +#define EDMA_STREAM2_LL_BASE (EDMA_LL_BASE + 0x0008) +#define EDMA_STREAM3_LL_BASE (EDMA_LL_BASE + 0x000C) +#define EDMA_STREAM4_LL_BASE (EDMA_LL_BASE + 0x0010) +#define EDMA_STREAM5_LL_BASE (EDMA_LL_BASE + 0x0014) +#define EDMA_STREAM6_LL_BASE (EDMA_LL_BASE + 0x0018) +#define EDMA_STREAM7_LL_BASE (EDMA_LL_BASE + 0x001C) +#define EDMA_STREAM8_LL_BASE (EDMA_LL_BASE + 0x0020) + +#define EDMAMUX_BASE (EDMA_BASE + 0x0140) +#define EDMAMUX_CHANNEL1_BASE (EDMAMUX_BASE) +#define EDMAMUX_CHANNEL2_BASE (EDMAMUX_BASE + 0x0004) +#define EDMAMUX_CHANNEL3_BASE (EDMAMUX_BASE + 0x0008) +#define EDMAMUX_CHANNEL4_BASE (EDMAMUX_BASE + 0x000C) +#define EDMAMUX_CHANNEL5_BASE (EDMAMUX_BASE + 0x0010) +#define EDMAMUX_CHANNEL6_BASE (EDMAMUX_BASE + 0x0014) +#define EDMAMUX_CHANNEL7_BASE (EDMAMUX_BASE + 0x0018) +#define EDMAMUX_CHANNEL8_BASE (EDMAMUX_BASE + 0x001C) + +#define EDMAMUX_GENERATOR1_BASE (EDMA_BASE + 0x0160) +#define EDMAMUX_GENERATOR2_BASE (EDMA_BASE + 0x0164) +#define EDMAMUX_GENERATOR3_BASE (EDMA_BASE + 0x0168) +#define EDMAMUX_GENERATOR4_BASE (EDMA_BASE + 0x016C) + +#define FLASH_REG_BASE (AHBPERIPH1_BASE + 0x3C00) +#define CRM_BASE (AHBPERIPH1_BASE + 0x3800) +#define CRC_BASE (AHBPERIPH1_BASE + 0x3000) +#define SDIO2_BASE (AHBPERIPH2_BASE + 0x61000) +#define DVP_BASE (AHBPERIPH2_BASE + 0x50000) +#define OTGFS1_BASE (AHBPERIPH2_BASE + 0x00000) + +#define EMAC_MAC_BASE (EMAC_BASE) +#define EMAC_MMC_BASE (EMAC_BASE + 0x0100) +#define EMAC_PTP_BASE (EMAC_BASE + 0x0700) +#define EMAC_DMA_BASE (EMAC_BASE + 0x1000) +#endif + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#include "at32f435_437_def.h" +#include "at32f435_437_conf.h" + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/src/main/startup/at32/at32f435_437_clock.c b/src/main/startup/at32/at32f435_437_clock.c new file mode 100644 index 0000000000..07b6f808fc --- /dev/null +++ b/src/main/startup/at32/at32f435_437_clock.c @@ -0,0 +1,117 @@ +/** + ************************************************************************** + * @file at32f435_437_clock.c + * @brief system clock config program + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437_clock.h" +#include "platform.h" +/** + * @brief system clock config program + * @note the system clock is configured as follow: + * - system clock = (hext * pll_ns)/(pll_ms * pll_fr) + * - system clock source = pll (hext) + * - hext = 8000000 + * - sclk = 288000000 + * - ahbdiv = 1 + * - ahbclk = 288000000 + * - apb1div = 2 + * - apb1clk = 144000000 + * - apb2div = 2 + * - apb2clk = 144000000 + * - pll_ns = 72 + * - pll_ms = 1 + * - pll_fr = 2 + * @param none + * @retval none + */ +void system_clock_config(void) +{ + /* enable pwc periph clock */ + crm_periph_clock_enable(CRM_PWC_PERIPH_CLOCK, TRUE); + + /* config ldo voltage */ + pwc_ldo_output_voltage_set(PWC_LDO_OUTPUT_1V3); + + /* set the flash clock divider */ + flash_clock_divider_set(FLASH_CLOCK_DIV_3); + + /* reset crm */ + crm_reset(); + + /* enable hext */ + crm_clock_source_enable(CRM_CLOCK_SOURCE_HEXT, TRUE); + + /* wait till hext is ready */ + while(crm_hext_stable_wait() == ERROR) + { + } + + /* enable hick */ + crm_clock_source_enable(CRM_CLOCK_SOURCE_HICK, TRUE); + + /* wait till hick is ready */ + while(crm_flag_get(CRM_HICK_STABLE_FLAG) != SET) + { + } + + /* config pll clock resource */ + crm_pll_config(CRM_PLL_SOURCE_HEXT, 72, 1, CRM_PLL_FR_2); + + /* enable pll */ + crm_clock_source_enable(CRM_CLOCK_SOURCE_PLL, TRUE); + + /* wait till pll is ready */ + while(crm_flag_get(CRM_PLL_STABLE_FLAG) != SET) + { + } + + /* config ahbclk */ + crm_ahb_div_set(CRM_AHB_DIV_1); + + /* config apb2clk */ + crm_apb2_div_set(CRM_APB2_DIV_2); + + /* config apb1clk */ + crm_apb1_div_set(CRM_APB1_DIV_2); + + /* enable auto step mode */ + crm_auto_step_mode_enable(TRUE); + + /* select pll as system clock source */ + crm_sysclk_switch(CRM_SCLK_PLL); + + /* wait till pll is used as system clock source */ + while(crm_sysclk_switch_status_get() != CRM_SCLK_PLL) + { + } + + /* disable auto step mode */ + crm_auto_step_mode_enable(FALSE); + + /* config usbclk from pll */ + crm_usb_clock_div_set(CRM_USB_DIV_6); + crm_usb_clock_source_select(CRM_USB_CLOCK_SOURCE_PLL); + + /* update system_core_clock global variable */ + system_core_clock_update(); +} diff --git a/src/main/startup/at32/at32f435_437_clock.h b/src/main/startup/at32/at32f435_437_clock.h new file mode 100644 index 0000000000..e3d852a002 --- /dev/null +++ b/src/main/startup/at32/at32f435_437_clock.h @@ -0,0 +1,44 @@ +/** + ************************************************************************** + * @file at32f435_437_clock.h + * @brief header file of clock program + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_CLOCK_H +#define __AT32F435_437_CLOCK_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/* exported functions ------------------------------------------------------- */ +void system_clock_config(void); + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/src/main/startup/at32/at32f435_437_conf.h b/src/main/startup/at32/at32f435_437_conf.h new file mode 100644 index 0000000000..a61b3ef691 --- /dev/null +++ b/src/main/startup/at32/at32f435_437_conf.h @@ -0,0 +1,180 @@ +/** + ************************************************************************** + * @file at32f435_437_conf.h + * @brief at32f435_437 config header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_CONF_H +#define __AT32F435_437_CONF_H + +#ifdef __cplusplus +extern "C" { +#endif + + +#ifndef NULL +#ifdef __cplusplus +#define NULL 0 +#else +#define NULL ((void *) 0) +#endif +#endif + +/** + * @brief in the following line adjust the value of high speed exernal crystal (hext) + * used in your application + * tip: to avoid modifying this file each time you need to use different hext, you + * can define the hext value in your toolchain compiler preprocessor. + */ +#if !defined HEXT_VALUE +#define HEXT_VALUE ((uint32_t)8000000) /*!< value of the high speed exernal crystal in hz */ +#endif + +/** + * @brief in the following line adjust the high speed exernal crystal (hext) startup + * timeout value + */ +#define HEXT_STARTUP_TIMEOUT ((uint16_t)0x3000) /*!< time out for hext start up */ +#define HICK_VALUE ((uint32_t)8000000) /*!< value of the high speed internal clock in hz */ + +/* module define -------------------------------------------------------------*/ +#define CRM_MODULE_ENABLED +#define TMR_MODULE_ENABLED +#define ERTC_MODULE_ENABLED +#define GPIO_MODULE_ENABLED +#define I2C_MODULE_ENABLED +#define USART_MODULE_ENABLED +#define PWC_MODULE_ENABLED +#define CAN_MODULE_ENABLED +#define ADC_MODULE_ENABLED +#define DAC_MODULE_ENABLED +#define SPI_MODULE_ENABLED +#define EDMA_MODULE_ENABLED +#define DMA_MODULE_ENABLED +#define DEBUG_MODULE_ENABLED +#define FLASH_MODULE_ENABLED +#define CRC_MODULE_ENABLED +#define WWDT_MODULE_ENABLED +#define WDT_MODULE_ENABLED +#define EXINT_MODULE_ENABLED +#define SDIO_MODULE_ENABLED +#define XMC_MODULE_ENABLED +#define USB_MODULE_ENABLED +#define ACC_MODULE_ENABLED +#define MISC_MODULE_ENABLED +#define QSPI_MODULE_ENABLED +#define DVP_MODULE_ENABLED +#define SCFG_MODULE_ENABLED +#define EMAC_MODULE_ENABLED + +/* includes ------------------------------------------------------------------*/ +#ifdef CRM_MODULE_ENABLED +#include "at32f435_437_crm.h" +#include "at32f435_437_rcc_periph.h" +#endif +#ifdef TMR_MODULE_ENABLED +#include "at32f435_437_tmr.h" +#endif +#ifdef ERTC_MODULE_ENABLED +#include "at32f435_437_ertc.h" +#endif +#ifdef GPIO_MODULE_ENABLED +#include "at32f435_437_gpio.h" +#endif +#ifdef I2C_MODULE_ENABLED +#include "at32f435_437_i2c.h" +#endif +#ifdef USART_MODULE_ENABLED +#include "at32f435_437_usart.h" +#endif +#ifdef PWC_MODULE_ENABLED +#include "at32f435_437_pwc.h" +#endif +#ifdef CAN_MODULE_ENABLED +#include "at32f435_437_can.h" +#endif +#ifdef ADC_MODULE_ENABLED +#include "at32f435_437_adc.h" +#endif +#ifdef DAC_MODULE_ENABLED +#include "at32f435_437_dac.h" +#endif +#ifdef SPI_MODULE_ENABLED +#include "at32f435_437_spi.h" +#endif +#ifdef DMA_MODULE_ENABLED +#include "at32f435_437_dma.h" +#endif +#ifdef DEBUG_MODULE_ENABLED +#include "at32f435_437_debug.h" +#endif +#ifdef FLASH_MODULE_ENABLED +#include "at32f435_437_flash.h" +#endif +#ifdef CRC_MODULE_ENABLED +#include "at32f435_437_crc.h" +#endif +#ifdef WWDT_MODULE_ENABLED +#include "at32f435_437_wwdt.h" +#endif +#ifdef WDT_MODULE_ENABLED +#include "at32f435_437_wdt.h" +#endif +#ifdef EXINT_MODULE_ENABLED +#include "at32f435_437_exint.h" +#endif +#ifdef SDIO_MODULE_ENABLED +#include "at32f435_437_sdio.h" +#endif +#ifdef XMC_MODULE_ENABLED +#include "at32f435_437_xmc.h" +#endif +#ifdef ACC_MODULE_ENABLED +#include "at32f435_437_acc.h" +#endif +#ifdef MISC_MODULE_ENABLED +#include "at32f435_437_misc.h" +#endif +#ifdef EDMA_MODULE_ENABLED +#include "at32f435_437_edma.h" +#endif +#ifdef QSPI_MODULE_ENABLED +#include "at32f435_437_qspi.h" +#endif +#ifdef SCFG_MODULE_ENABLED +#include "at32f435_437_scfg.h" +#endif +#ifdef EMAC_MODULE_ENABLED +#include "at32f435_437_emac.h" +#endif +#ifdef DVP_MODULE_ENABLED +#include "at32f435_437_dvp.h" +#endif +#ifdef USB_MODULE_ENABLED +#include "at32f435_437_usb.h" +#endif + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/src/main/startup/at32/startup_at32f435_437.s b/src/main/startup/at32/startup_at32f435_437.s new file mode 100644 index 0000000000..d8f7024483 --- /dev/null +++ b/src/main/startup/at32/startup_at32f435_437.s @@ -0,0 +1,571 @@ +/** + ****************************************************************************** + * @file startup_at32f435_437.s + * @version v2.0.4 + * @date 2021-12-31 + * @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 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 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 diff --git a/src/main/startup/at32/system_at32f435_437.c b/src/main/startup/at32/system_at32f435_437.c new file mode 100644 index 0000000000..8d2dbddf91 --- /dev/null +++ b/src/main/startup/at32/system_at32f435_437.c @@ -0,0 +1,186 @@ +/** + ************************************************************************** + * @file system_at32f435_437.c + * @version v2.0.4 + * @date 2021-12-31 + * @brief contains all the functions for cmsis cortex-m4 system source file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup AT32F435_437_system + * @{ + */ + +#include "at32f435_437.h" +#include "platform.h" + +/** @addtogroup AT32F435_437_system_private_defines + * @{ + */ +#define VECT_TAB_OFFSET 0x0 /*!< vector table base offset field. this value must be a multiple of 0x200. */ +/** + * @} + */ + +/** @addtogroup AT32F435_437_system_private_variables + * @{ + */ +unsigned int system_core_clock = HICK_VALUE; /*!< system clock frequency (core clock) */ +/** + * @} + */ + +/** @addtogroup AT32F435_437_system_private_functions + * @{ + */ + +/** + * @brief setup the microcontroller system + * initialize the flash interface. + * @note this function should be used only after reset. + * @param none + * @retval none + */ +void SystemInit (void) +{ +#if defined (__FPU_USED) && (__FPU_USED == 1U) + SCB->CPACR |= ((3U << 10U * 2U) | /* set cp10 full access */ + (3U << 11U * 2U) ); /* set cp11 full access */ +#endif + + /* reset the crm clock configuration to the default reset state(for debug purpose) */ + /* set hicken bit */ + CRM->ctrl_bit.hicken = TRUE; + + /* wait hick stable */ + while(CRM->ctrl_bit.hickstbl != SET); + + /* hick used as system clock */ + CRM->cfg_bit.sclksel = CRM_SCLK_HICK; + + /* wait sclk switch status */ + while(CRM->cfg_bit.sclksts != CRM_SCLK_HICK); + + /* reset cfg register, include sclk switch, ahbdiv, apb1div, apb2div, adcdiv, clkout bits */ + CRM->cfg = 0; + + /* reset hexten, hextbyps, cfden and pllen bits */ + CRM->ctrl &= ~(0x010D0000U); + + /* reset pllms pllns pllfr pllrcs bits */ + CRM->pllcfg = 0x00033002U; + + /* reset clkout[3], usbbufs, hickdiv, clkoutdiv */ + CRM->misc1 = 0; + + /* disable all interrupts enable and clear pending bits */ + CRM->clkint = 0x009F0000U; + +#ifdef VECT_TAB_SRAM + SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* vector table relocation in internal sram. */ +#else + SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* vector table relocation in internal flash. */ +#endif +} + +/** + * @brief update system_core_clock variable according to clock register values. + * the system_core_clock variable contains the core clock (hclk), it can + * be used by the user application to setup the systick timer or configure + * other parameters. + * @param none + * @retval none + */ +void system_core_clock_update(void) +{ + uint32_t pll_ns = 0, pll_ms = 0, pll_fr = 0, pll_clock_source = 0, pllrcsfreq = 0; + uint32_t temp = 0, div_value = 0; + crm_sclk_type sclk_source; + + static const uint8_t sys_ahb_div_table[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; + static const uint8_t pll_fr_table[6] = {1, 2, 4, 8, 16, 32}; + + /* get sclk source */ + sclk_source = crm_sysclk_switch_status_get(); + + switch(sclk_source) + { + case CRM_SCLK_HICK: + if(((CRM->misc1_bit.hick_to_sclk) != RESET) && ((CRM->misc1_bit.hickdiv) != RESET)) + system_core_clock = HICK_VALUE * 6; + else + system_core_clock = HICK_VALUE; + break; + case CRM_SCLK_HEXT: + system_core_clock = HEXT_VALUE; + break; + case CRM_SCLK_PLL: + /* get pll clock source */ + pll_clock_source = CRM->pllcfg_bit.pllrcs; + + /* get multiplication factor */ + pll_ns = CRM->pllcfg_bit.pllns; + pll_ms = CRM->pllcfg_bit.pllms; + pll_fr = pll_fr_table[CRM->pllcfg_bit.pllfr]; + + if (pll_clock_source == CRM_PLL_SOURCE_HICK) + { + /* hick selected as pll clock entry */ + pllrcsfreq = HICK_VALUE; + } + else + { + /* hext selected as pll clock entry */ + pllrcsfreq = HEXT_VALUE; + } + + system_core_clock = (pllrcsfreq * pll_ns) / (pll_ms * pll_fr); + break; + default: + system_core_clock = HICK_VALUE; + break; + } + + /* compute sclk, ahbclk frequency */ + /* get ahb division */ + temp = CRM->cfg_bit.ahbdiv; + div_value = sys_ahb_div_table[temp]; + /* ahbclk frequency */ + system_core_clock = system_core_clock >> div_value; +} + +extern void _init(void) {;} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + diff --git a/src/main/startup/at32/system_at32f435_437.h b/src/main/startup/at32/system_at32f435_437.h new file mode 100644 index 0000000000..eedeb0b27e --- /dev/null +++ b/src/main/startup/at32/system_at32f435_437.h @@ -0,0 +1,75 @@ +/** + ************************************************************************** + * @file system_at32f435_437.h + * @version v2.0.4 + * @date 2021-12-31 + * @brief cmsis cortex-m4 system header file. + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#ifndef __SYSTEM_AT32F435_437_H +#define __SYSTEM_AT32F435_437_H + +#ifdef __cplusplus +extern "C" { +#endif + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup AT32F435_437_system + * @{ + */ + +/** @defgroup AT32F435_437_system_exported_variables + * @{ + */ +extern unsigned int system_core_clock; /*!< system clock frequency (core clock) */ + +/** + * @} + */ + +/** @defgroup AT32F435_437_system_exported_functions + * @{ + */ + +extern void SystemInit(void); +extern void system_core_clock_update(void); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/src/main/target/AT32F435/target.c b/src/main/target/AT32F435/target.c new file mode 100644 index 0000000000..a087e06bd2 --- /dev/null +++ b/src/main/target/AT32F435/target.c @@ -0,0 +1,22 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +// Needed to suppress the pedantic warning about an empty file +#include diff --git a/src/main/target/AT32F435/target.h b/src/main/target/AT32F435/target.h new file mode 100644 index 0000000000..014b67795e --- /dev/null +++ b/src/main/target/AT32F435/target.h @@ -0,0 +1,105 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "A435" + +#define USBD_PRODUCT_STRING "Betaflight AT32F435" + +#ifndef AT32F435 +#define AT32F435 +#endif + +// AT-START-F435 V1.0 LED assignments to use as a default +#define LED0_PIN PD13 // Labelled LED2 Red +#define LED1_PIN PD14 // Labelled LED3 Amber +#define LED2_PIN PD15 // Labelled LED4 Green + +//#define USE_I2C_DEVICE_1 + +#define USE_UART1 +// AT-START-F435 V1.0 UART 1 assignments to use as a default +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 +#define USE_MSP_UART SERIAL_PORT_USART1 + +#define USE_UART2 +#define USE_UART3 +#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 3) + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff + +//#define USE_I2C +//#define I2C_FULL_RECONFIGURABILITY + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 +#define SPI_FULL_RECONFIGURABILITY + +//#define USE_USB_DETECT +//#define USE_VCP +//#define USE_SOFTSERIAL1 +//#define USE_SOFTSERIAL2 + + +#define UNIFIED_SERIAL_PORT_COUNT 0 + +//#define USE_ADC + +#define USE_CUSTOM_DEFAULTS +#define USE_TIMER_MGMT +#define USE_PWM_OUTPUT + +#undef USE_BEEPER +#undef USE_LED_STRIP +#undef USE_TRANSPONDER +#undef USE_DSHOT +#undef USE_CAMERA_CONTROL +#undef USE_RX_PPM +#undef USE_RX_PWM +#undef USE_RX_SPI +#undef USE_RX_CC2500 +#undef USE_RX_EXPRESSLRS +#undef USE_CMS +#undef USE_OSD +#undef USE_BLACKBOX +#undef USE_SDCARD +#undef USE_BARO +#undef USE_MAG +#undef USE_SERIAL_4WAY_BLHELI_BOOTLOADER +#undef USE_SERIAL_4WAY_SK_BOOTLOADER + +// remove all flash +#undef USE_FLASH +#undef USE_FLASHFS +#undef USE_FLASH_CHIP + +#if defined(AT32F435ZMT7) || defined(AT32F435RMT7) +// 4k sectors +#define FLASH_PAGE_SIZE ((uint32_t)0x1000) +#elif defined(AT32F435RGT7) +// 2K page sectors +#define FLASH_PAGE_SIZE ((uint32_t)0x0800) +#endif diff --git a/src/main/target/AT32F435/target.mk b/src/main/target/AT32F435/target.mk new file mode 100644 index 0000000000..80633b20ab --- /dev/null +++ b/src/main/target/AT32F435/target.mk @@ -0,0 +1,41 @@ +CMSIS_DIR := $(ROOT)/lib/main/AT32F43x/cmsis +TARGET_MCU := AT32F435 +MCU_FLASH_SIZE := 4032 +DEVICE_FLAGS = -DAT32F435ZMT7 +TARGET_MCU_FAMILY := AT32F4 + +STDPERIPH_DIR = $(ROOT)/lib/main/AT32F43x/drivers +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) +EXCLUDES = at32f435_437_dvp.c \ + at32f435_437_can.c \ + at32f435_437_xmc.c \ + at32f435_437_emac + +STARTUP_SRC = at32/startup_at32f435_437.s +STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) + +VPATH := $(VPATH):$(ROOT)/lib/main/AT32F43x/cmsis/cm4/core_support:$(STDPERIPH_DIR)/inc:$(SRC_DIR)/startup/at32 + +INCLUDE_DIRS := $(INCLUDE_DIRS) \ + $(SRC_DIR)/startup/at32 \ + $(STDPERIPH_DIR)/inc \ + $(ROOT)/lib/main/AT32F43x/cmsis/cm4/core_support \ + $(ROOT)/lib/main/AT32F43x/cmsis/cm4 + +DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC) + +LD_SCRIPT = $(LINKER_DIR)/at32_flash_f43xM.ld + +ARCH_FLAGS = -std=c99 -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion +DEVICE_FLAGS += -DUSE_ATBSP_DRIVER -DAT32F43x -DHSE_VALUE=$(HSE_VALUE) + +MCU_COMMON_SRC = \ + $(addprefix startup/at32/,$(notdir $(wildcard $(SRC_DIR)/startup/at32/*.c))) \ + $(addprefix drivers/at32/,$(notdir $(wildcard $(SRC_DIR)/drivers/at32/*.c))) + +MCU_EXCLUDES = \ + drivers/bus_i2c.c \ + drivers/timer.c \ + drivers/persistent.c \ + drivers/pwm_output.c + diff --git a/src/main/target/common_pre.h b/src/main/target/common_pre.h index ab2971733d..d44c1ddd68 100644 --- a/src/main/target/common_pre.h +++ b/src/main/target/common_pre.h @@ -59,6 +59,15 @@ #define USE_DSHOT_TELEMETRY_STATS #endif +#ifdef AT32F4 + +#define USE_TIMER_MGMT +#define USE_DMA_SPEC +#define USE_PERSISTENT_OBJECTS +#define USE_CUSTOM_DEFAULTS_ADDRESS + +#endif + #ifdef STM32F4 #if defined(STM32F40_41xxx) #define USE_FAST_DATA @@ -305,9 +314,15 @@ extern uint8_t _dmaram_end__; #endif #endif -#if !defined(USE_EXST) && !defined(USE_FLASH) -#define USE_FLASHFS +#if defined(USE_FLASH_CHIP) +#if !defined(USE_EXST) && !defined(USE_FLASH) +#define USE_FLASH +#endif + +#if defined(USE_FLASH) + +#define USE_FLASHFS #define USE_FLASH_TOOLS #define USE_FLASH_M25P16 #define USE_FLASH_W25N01G // 1Gb NAND flash support @@ -316,6 +331,7 @@ extern uint8_t _dmaram_end__; #define USE_FLASH_W25M02G // 2Gb (1Gb x 2 stacked) NAND flash support #define USE_FLASH_W25Q128FV // 16MB Winbond 25Q128 +#endif #endif #ifndef USE_MAX7456