commit 8aea82883866db5412b8aa5f6928f13cdeb611ff Author: Yilin Sun Date: Sun Mar 17 21:35:25 2024 +0800 Initial commit. Signed-off-by: Yilin Sun diff --git a/.clang-format b/.clang-format new file mode 100644 index 0000000..214adf0 --- /dev/null +++ b/.clang-format @@ -0,0 +1,12 @@ +BasedOnStyle: Google +IndentWidth: 4 +AlignConsecutiveMacros: Consecutive +AlignConsecutiveDeclarations: Consecutive +AlignConsecutiveAssignments: Consecutive +AllowShortFunctionsOnASingleLine: None +BreakBeforeBraces: Custom +BraceWrapping: + AfterEnum: false + AfterStruct: false + SplitEmptyFunction: false +ColumnLimit: 120 \ No newline at end of file diff --git a/.drone.yml b/.drone.yml new file mode 100644 index 0000000..94e5a4b --- /dev/null +++ b/.drone.yml @@ -0,0 +1,17 @@ +--- +kind: pipeline +type: docker +name: Build + +steps: + - name: Submodules + image: alpine/git + commands: + - git submodule update --init --recursive + + - name: Build + image: "git.minori.work/embedded_sdk/embedded-builder-arm:12.2.mpacbti-rel1" + commands: + - mkdir build && cd build + - cmake -DCMAKE_TOOLCHAIN_FILE=arm-none-eabi.cmake .. + - make diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..ee1fbdd --- /dev/null +++ b/.gitignore @@ -0,0 +1,6 @@ +/board/*.bak +/build +/cmake-build-* +/.vscode +/*.jdebug* +/*.jflash \ No newline at end of file diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 0000000..6abf64e --- /dev/null +++ b/.gitmodules @@ -0,0 +1,3 @@ +[submodule "SDK"] + path = SDK + url = https://github.com/STMicroelectronics/STM32CubeMP1.git diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..5f2e5a3 --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,167 @@ +cmake_minimum_required(VERSION 3.10) + +project(pangu_m4_template) + +enable_language(CXX) +enable_language(ASM) + +# Different linker scripts +set(TARGET_LDSCRIPT "${CMAKE_SOURCE_DIR}/GCC/stm32mp15xx_m4.ld") + +set(TARGET_SOURCES + "GCC/startup_stm32mp15xx.s" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_adc.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_adc_ex.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_cec.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_cortex.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_crc.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_crc_ex.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_cryp.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_cryp_ex.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_dac.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_dac_ex.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_dcmi.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_dfsdm.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_dfsdm_ex.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_dma.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_dma_ex.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_exti.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_fdcan.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_gpio.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_hash.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_hash_ex.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_hsem.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_i2c.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_i2c_ex.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_ipcc.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_lptim.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_mdios.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_mdma.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_pwr.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_pwr_ex.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_qspi.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_rcc.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_rcc_ex.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_rng.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_rtc.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_rtc_ex.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_sai.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_sai_ex.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_sd.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_sd_ex.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_smartcard.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_smartcard_ex.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_smbus.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_smbus_ex.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_spdifrx.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_spi.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_spi_ex.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_sram.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_tim.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_tim_ex.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_uart.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_uart_ex.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_usart.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_usart_ex.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_hal_wwdg.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_ll_adc.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_ll_delayblock.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_ll_dma.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_ll_exti.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_ll_fmc.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_ll_gpio.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_ll_i2c.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_ll_lptim.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_ll_pwr.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_ll_rcc.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_ll_rtc.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_ll_sdmmc.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_ll_spi.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_ll_tim.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_ll_usart.c" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Src/stm32mp1xx_ll_utils.c" + "board/board.c" + "board/clock_config.c" + "board/peripherals.c" + "board/pin_mux.c" + "board/stm32mp1xx_it.c" + "board/system_stm32mp1xx.c" + "src/main.c" + "src/syscalls.c" +) + +set(TARGET_C_DEFINES + "CORE_CM4" + "STM32MP157Axx" + "USE_HAL_DRIVER" +) + +set(TARGET_C_INCLUDES + "SDK/Drivers/CMSIS/Core/Include" + "SDK/Drivers/CMSIS/Device/ST/STM32MP1xx/Include" + "SDK/Drivers/STM32MP1xx_HAL_Driver/Inc" + "board" + "include" +) + +# Shared libraries linked with application +set(TARGET_LIBS + "c" + "m" + "nosys" +) + +# Shared library and linker script search paths +set(TARGET_LIB_DIRECTORIES + +) + +# Conditional flags +# DEBUG +set(CMAKE_C_FLAGS_DEBUG "-DDEBUG -O0 -g") +set(CMAKE_CXX_FLAGS_DEBUG "-DDEBUG -O0 -g") +set(CMAKE_ASM_FLAGS_DEBUG "-DDEBUG -O0 -g") + +# RELEASE +set(CMAKE_C_FLAGS_RELEASE "-DNDEBUG -O2") +set(CMAKE_CXX_FLAGS_RELEASE "-DNDEBUG -O2") +set(CMAKE_ASM_FLAGS_RELEASE "-DNDEBUG -O2") +set(CMAKE_EXE_LINKER_FLAGS_RELEASE "") + +# Final compiler flags +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -fno-common -fno-builtin -ffreestanding -fdata-sections -ffunction-sections") +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -fno-common -fno-builtin -ffreestanding -fdata-sections -ffunction-sections") +set(CMAKE_ASM_FLAGS "${CMAKE_C_FLAGS} -x assembler-with-cpp") +set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -Wl,--gc-sections") + +# Shared sources, includes and definitions +add_compile_definitions(${TARGET_C_DEFINES}) +include_directories(${TARGET_C_INCLUDES}) +link_directories(${TARGET_LIB_DIRECTORIES}) +link_libraries(${TARGET_LIBS}) + +# Main targets are added here + +# Create ELF +add_executable("${CMAKE_PROJECT_NAME}.elf" ${TARGET_SOURCES}) +target_compile_definitions("${CMAKE_PROJECT_NAME}.elf" + PRIVATE ${TARGET_C_DEFINES_XIP} + ) +target_link_options("${CMAKE_PROJECT_NAME}.elf" + PRIVATE "-T${TARGET_LDSCRIPT}" + PRIVATE "-Wl,--Map=${CMAKE_PROJECT_NAME}.map" + ) +set_property(TARGET "${CMAKE_PROJECT_NAME}.elf" APPEND + PROPERTY ADDITIONAL_CLEAN_FILES "${CMAKE_PROJECT_NAME}.map" + ) +add_custom_command(OUTPUT "${CMAKE_PROJECT_NAME}.hex" + COMMAND ${CMAKE_OBJCOPY} "-O" "ihex" "${CMAKE_PROJECT_NAME}.elf" "${CMAKE_PROJECT_NAME}.hex" + DEPENDS "${CMAKE_PROJECT_NAME}.elf" + ) +add_custom_target("${CMAKE_PROJECT_NAME}_HEX" DEPENDS "${CMAKE_PROJECT_NAME}.hex") +if(DEFINED TARGET_TOOLCHAIN_SIZE) + add_custom_command(TARGET "${CMAKE_PROJECT_NAME}.elf" POST_BUILD + COMMAND ${TARGET_TOOLCHAIN_SIZE} "${CMAKE_PROJECT_NAME}.elf" + ) +endif() diff --git a/GCC/startup_stm32mp15xx.s b/GCC/startup_stm32mp15xx.s new file mode 100644 index 0000000..149dce1 --- /dev/null +++ b/GCC/startup_stm32mp15xx.s @@ -0,0 +1,789 @@ +/** + ****************************************************************************** + * @file startup_stm32mp15xx.s + * @author MCD Application Team + * @brief STM32MP15xx Devices vector table for GCC based toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * Copyright (c) 2021 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + * + ****************************************************************************** + */ + + .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 + + .section .startup_copro_fw.Reset_Handler,"ax" + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + ldr sp, =_estack /* set stack pointer */ + +/* Loop to copy data from read only memory to RAM. The ranges + * of copy from/to are specified by following symbols evaluated in + * linker script. + * _sidata: End of code section, i.e., begin of data sections to copy from. + * _sdata/_edata: RAM address range that data should be + * copied to. Both must be aligned to 4 bytes boundary. */ + 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 + // ldr r0, =SystemInit + // blx r0 +/* Call static constructors */ + bl __libc_init_array + // ldr r0, =__libc_init_array + // blx r0 +/* Call the application's entry point.*/ + bl main + //ldr r0, =main + //blx r0 + +LoopForever: + b LoopForever + + +.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 M4. 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 // Top of Stack + .word Reset_Handler // Reset Handler + .word NMI_Handler // NMI Handler + .word HardFault_Handler // Hard Fault Handler + .word MemManage_Handler // MPU Fault Handler + .word BusFault_Handler // Bus Fault Handler + .word UsageFault_Handler // Usage Fault Handler + .word 0 // Reserved + .word 0 // Reserved + .word 0 // Reserved + .word 0 // Reserved + .word SVC_Handler // SVCall Handler + .word DebugMon_Handler // Debug Monitor Handler + .word 0 // Reserved + .word PendSV_Handler // PendSV Handler + .word SysTick_Handler // SysTick Handler + + // External Interrupts + .word WWDG1_IRQHandler // Window WatchDog 1 + .word PVD_AVD_IRQHandler // PVD and AVD through EXTI Line detection + .word TAMP_IRQHandler // Tamper and TimeStamps through the EXTI line + .word RTC_WKUP_ALARM_IRQHandler // RTC Wakeup and Alarm through the EXTI line + .word RESERVED4_IRQHandler // Reserved + .word RCC_IRQHandler // RCC + .word EXTI0_IRQHandler // EXTI Line0 + .word EXTI1_IRQHandler // EXTI Line1 + .word EXTI2_IRQHandler // EXTI Line2 + .word EXTI3_IRQHandler // EXTI Line3 + .word EXTI4_IRQHandler // EXTI Line4 + .word DMA1_Stream0_IRQHandler // DMA1 Stream 0 + .word DMA1_Stream1_IRQHandler // DMA1 Stream 1 + .word DMA1_Stream2_IRQHandler // DMA1 Stream 2 + .word DMA1_Stream3_IRQHandler // DMA1 Stream 3 + .word DMA1_Stream4_IRQHandler // DMA1 Stream 4 + .word DMA1_Stream5_IRQHandler // DMA1 Stream 5 + .word DMA1_Stream6_IRQHandler // DMA1 Stream 6 + .word ADC1_IRQHandler // ADC1 + .word FDCAN1_IT0_IRQHandler // FDCAN1 Interrupt line 0 + .word FDCAN2_IT0_IRQHandler // FDCAN2 Interrupt line 0 + .word FDCAN1_IT1_IRQHandler // FDCAN1 Interrupt line 1 + .word FDCAN2_IT1_IRQHandler // FDCAN2 Interrupt line 1 + .word EXTI5_IRQHandler // External Line5 interrupts through AIEC + .word TIM1_BRK_IRQHandler // TIM1 Break interrupt + .word TIM1_UP_IRQHandler // TIM1 Update Interrupt + .word TIM1_TRG_COM_IRQHandler // TIM1 Trigger and Commutation Interrupt + .word TIM1_CC_IRQHandler // TIM1 Capture Compare + .word TIM2_IRQHandler // TIM2 + .word TIM3_IRQHandler // TIM3 + .word TIM4_IRQHandler // TIM4 + .word I2C1_EV_IRQHandler // I2C1 Event + .word I2C1_ER_IRQHandler // I2C1 Error + .word I2C2_EV_IRQHandler // I2C2 Event + .word I2C2_ER_IRQHandler // I2C2 Error + .word SPI1_IRQHandler // SPI1 + .word SPI2_IRQHandler // SPI2 + .word USART1_IRQHandler // USART1 + .word USART2_IRQHandler // USART2 + .word USART3_IRQHandler // USART3 + .word EXTI10_IRQHandler // External Line10 interrupts through AIEC + .word RTC_TIMESTAMP_IRQHandler // RTC TimeStamp through EXTI Line + .word EXTI11_IRQHandler // External Line11 interrupts through AIEC + .word TIM8_BRK_IRQHandler // TIM8 Break Interrupt + .word TIM8_UP_IRQHandler // TIM8 Update Interrupt + .word TIM8_TRG_COM_IRQHandler // TIM8 Trigger and Commutation Interrupt + .word TIM8_CC_IRQHandler // TIM8 Capture Compare Interrupt + .word DMA1_Stream7_IRQHandler // DMA1 Stream7 + .word FMC_IRQHandler // FMC + .word SDMMC1_IRQHandler // SDMMC1 + .word TIM5_IRQHandler // TIM5 + .word SPI3_IRQHandler // SPI3 + .word UART4_IRQHandler // UART4 + .word UART5_IRQHandler // UART5 + .word TIM6_IRQHandler // TIM6 + .word TIM7_IRQHandler // TIM7 + .word DMA2_Stream0_IRQHandler // DMA2 Stream 0 + .word DMA2_Stream1_IRQHandler // DMA2 Stream 1 + .word DMA2_Stream2_IRQHandler // DMA2 Stream 2 + .word DMA2_Stream3_IRQHandler // DMA2 Stream 3 + .word DMA2_Stream4_IRQHandler // DMA2 Stream 4 + .word ETH1_IRQHandler // Ethernet + .word ETH1_WKUP_IRQHandler // Ethernet Wakeup through EXTI line + .word FDCAN_CAL_IRQHandler // FDCAN Calibration + .word EXTI6_IRQHandler // EXTI Line6 interrupts through AIEC + .word EXTI7_IRQHandler // EXTI Line7 interrupts through AIEC + .word EXTI8_IRQHandler // EXTI Line8 interrupts through AIEC + .word EXTI9_IRQHandler // EXTI Line9 interrupts through AIEC + .word DMA2_Stream5_IRQHandler // DMA2 Stream 5 + .word DMA2_Stream6_IRQHandler // DMA2 Stream 6 + .word DMA2_Stream7_IRQHandler // DMA2 Stream 7 + .word USART6_IRQHandler // USART6 + .word I2C3_EV_IRQHandler // I2C3 event + .word I2C3_ER_IRQHandler // I2C3 error + .word USBH_OHCI_IRQHandler // USB Host OHCI + .word USBH_EHCI_IRQHandler // USB Host EHCI + .word EXTI12_IRQHandler // EXTI Line12 interrupts through AIEC + .word EXTI13_IRQHandler // EXTI Line13 interrupts through AIEC + .word DCMI_IRQHandler // DCMI + .word CRYP1_IRQHandler // Crypto1 global interrupt + .word HASH1_IRQHandler // Crypto Hash1 interrupt + .word FPU_IRQHandler // FPU + .word UART7_IRQHandler // UART7 + .word UART8_IRQHandler // UART8 + .word SPI4_IRQHandler // SPI4 + .word SPI5_IRQHandler // SPI5 + .word SPI6_IRQHandler // SPI6 + .word SAI1_IRQHandler // SAI1 + .word LTDC_IRQHandler // LTDC + .word LTDC_ER_IRQHandler // LTDC error + .word ADC2_IRQHandler // ADC2 + .word SAI2_IRQHandler // SAI2 + .word QUADSPI_IRQHandler // QUADSPI + .word LPTIM1_IRQHandler // LPTIM1 global interrupt + .word CEC_IRQHandler // HDMI_CEC + .word I2C4_EV_IRQHandler // I2C4 Event + .word I2C4_ER_IRQHandler // I2C4 Error + .word SPDIF_RX_IRQHandler // SPDIF_RX + .word OTG_IRQHandler // USB On The Go HS global interrupt + .word RESERVED99_IRQHandler // Reserved + .word IPCC_RX0_IRQHandler // Mailbox RX0 Free interrupt + .word IPCC_TX0_IRQHandler // Mailbox TX0 Free interrupt + .word DMAMUX1_OVR_IRQHandler // DMAMUX1 Overrun interrupt + .word IPCC_RX1_IRQHandler // Mailbox RX1 Free interrupt + .word IPCC_TX1_IRQHandler // Mailbox TX1 Free interrupt + .word CRYP2_IRQHandler // Crypto2 global interrupt + .word HASH2_IRQHandler // Crypto Hash2 interrupt + .word I2C5_EV_IRQHandler // I2C5 Event Interrupt + .word I2C5_ER_IRQHandler // I2C5 Error Interrupt + .word GPU_IRQHandler // GPU Global Interrupt + .word DFSDM1_FLT0_IRQHandler // DFSDM Filter0 Interrupt + .word DFSDM1_FLT1_IRQHandler // DFSDM Filter1 Interrupt + .word DFSDM1_FLT2_IRQHandler // DFSDM Filter2 Interrupt + .word DFSDM1_FLT3_IRQHandler // DFSDM Filter3 Interrupt + .word SAI3_IRQHandler // SAI3 global Interrupt + .word DFSDM1_FLT4_IRQHandler // DFSDM Filter4 Interrupt + .word TIM15_IRQHandler // TIM15 global Interrupt + .word TIM16_IRQHandler // TIM16 global Interrupt + .word TIM17_IRQHandler // TIM17 global Interrupt + .word TIM12_IRQHandler // TIM12 global Interrupt + .word MDIOS_IRQHandler // MDIOS global Interrupt + .word EXTI14_IRQHandler // EXTI Line14 interrupts through AIEC + .word MDMA_IRQHandler // MDMA global Interrupt + .word DSI_IRQHandler // DSI global Interrupt + .word SDMMC2_IRQHandler // SDMMC2 global Interrupt + .word HSEM_IT2_IRQHandler // HSEM global Interrupt + .word DFSDM1_FLT5_IRQHandler // DFSDM Filter5 Interrupt + .word EXTI15_IRQHandler // EXTI Line15 interrupts through AIEC + .word nCTIIRQ1_IRQHandler // Cortex-M4 CTI interrupt 1 + .word nCTIIRQ2_IRQHandler // Cortex-M4 CTI interrupt 2 + .word TIM13_IRQHandler // TIM13 global interrupt + .word TIM14_IRQHandler // TIM14 global interrupt + .word DAC_IRQHandler // DAC1 and DAC2 underrun error interrupts + .word RNG1_IRQHandler // RNG1 interrupt + .word RNG2_IRQHandler // RNG2 interrupt + .word I2C6_EV_IRQHandler // I2C6 Event Interrupt + .word I2C6_ER_IRQHandler // I2C6 Error Interrupt + .word SDMMC3_IRQHandler // SDMMC3 global Interrupt + .word LPTIM2_IRQHandler // LPTIM2 global interrupt + .word LPTIM3_IRQHandler // LPTIM3 global interrupt + .word LPTIM4_IRQHandler // LPTIM4 global interrupt + .word LPTIM5_IRQHandler // LPTIM5 global interrupt + .word ETH1_LPI_IRQHandler // ETH1_LPI interrupt + .word RESERVED143_IRQHandler // Reserved + .word MPU_SEV_IRQHandler // MPU Send Event through AIEC + .word RCC_WAKEUP_IRQHandler // RCC Wake up interrupt + .word SAI4_IRQHandler // SAI4 global interrupt + .word DTS_IRQHandler // Temperature sensor interrupt + .word RESERVED148_IRQHandler // Reserved + .word WAKEUP_PIN_IRQHandler // Interrupt for all 6 wake-up pins + +/******************************************************************************* +* +* 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 RESERVED4_IRQHandler + .thumb_set RESERVED4_IRQHandler,Default_Handler + + .weak RESERVED99_IRQHandler + .thumb_set RESERVED99_IRQHandler,Default_Handler + + .weak ETH1_LPI_IRQHandler + .thumb_set ETH1_LPI_IRQHandler,Default_Handler + + .weak RESERVED143_IRQHandler + .thumb_set RESERVED143_IRQHandler,Default_Handler + + .weak WWDG1_IRQHandler + .thumb_set WWDG1_IRQHandler,Default_Handler + + .weak PVD_AVD_IRQHandler + .thumb_set PVD_AVD_IRQHandler,Default_Handler + + .weak TAMP_IRQHandler + .thumb_set TAMP_IRQHandler,Default_Handler + + .weak RTC_WKUP_ALARM_IRQHandler + .thumb_set RTC_WKUP_ALARM_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Stream0_IRQHandler + .thumb_set DMA1_Stream0_IRQHandler,Default_Handler + + .weak DMA1_Stream1_IRQHandler + .thumb_set DMA1_Stream1_IRQHandler,Default_Handler + + .weak DMA1_Stream2_IRQHandler + .thumb_set DMA1_Stream2_IRQHandler,Default_Handler + + .weak DMA1_Stream3_IRQHandler + .thumb_set DMA1_Stream3_IRQHandler,Default_Handler + + .weak DMA1_Stream4_IRQHandler + .thumb_set DMA1_Stream4_IRQHandler,Default_Handler + + .weak DMA1_Stream5_IRQHandler + .thumb_set DMA1_Stream5_IRQHandler,Default_Handler + + .weak DMA1_Stream6_IRQHandler + .thumb_set DMA1_Stream6_IRQHandler,Default_Handler + + .weak ADC1_IRQHandler + .thumb_set ADC1_IRQHandler,Default_Handler + + .weak ADC2_IRQHandler + .thumb_set ADC2_IRQHandler,Default_Handler + + .weak FDCAN1_IT0_IRQHandler + .thumb_set FDCAN1_IT0_IRQHandler,Default_Handler + + .weak FDCAN2_IT0_IRQHandler + .thumb_set FDCAN2_IT0_IRQHandler,Default_Handler + + .weak FDCAN1_IT1_IRQHandler + .thumb_set FDCAN1_IT1_IRQHandler,Default_Handler + + .weak FDCAN2_IT1_IRQHandler + .thumb_set FDCAN2_IT1_IRQHandler,Default_Handler + + .weak FDCAN_CAL_IRQHandler + .thumb_set FDCAN_CAL_IRQHandler,Default_Handler + + .weak EXTI5_IRQHandler + .thumb_set EXTI5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI10_IRQHandler + .thumb_set EXTI10_IRQHandler,Default_Handler + + .weak RTC_TIMESTAMP_IRQHandler + .thumb_set RTC_TIMESTAMP_IRQHandler,Default_Handler + + .weak EXTI11_IRQHandler + .thumb_set EXTI11_IRQHandler,Default_Handler + + .weak TIM8_BRK_IRQHandler + .thumb_set TIM8_BRK_IRQHandler,Default_Handler + + .weak TIM8_UP_IRQHandler + .thumb_set TIM8_UP_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_IRQHandler + .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak DMA1_Stream7_IRQHandler + .thumb_set DMA1_Stream7_IRQHandler,Default_Handler + + .weak FMC_IRQHandler + .thumb_set FMC_IRQHandler,Default_Handler + + .weak SDMMC1_IRQHandler + .thumb_set SDMMC1_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_IRQHandler + .thumb_set TIM6_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Stream0_IRQHandler + .thumb_set DMA2_Stream0_IRQHandler,Default_Handler + + .weak DMA2_Stream1_IRQHandler + .thumb_set DMA2_Stream1_IRQHandler,Default_Handler + + .weak DMA2_Stream2_IRQHandler + .thumb_set DMA2_Stream2_IRQHandler,Default_Handler + + .weak DMA2_Stream3_IRQHandler + .thumb_set DMA2_Stream3_IRQHandler,Default_Handler + + .weak DMA2_Stream4_IRQHandler + .thumb_set DMA2_Stream4_IRQHandler,Default_Handler + + .weak ETH1_IRQHandler + .thumb_set ETH1_IRQHandler,Default_Handler + + .weak ETH1_WKUP_IRQHandler + .thumb_set ETH1_WKUP_IRQHandler,Default_Handler + + .weak ETH1_LPI_IRQHandler + .thumb_set ETH1_LPI_IRQHandler,Default_Handler + + .weak EXTI6_IRQHandler + .thumb_set EXTI6_IRQHandler,Default_Handler + + .weak EXTI7_IRQHandler + .thumb_set EXTI7_IRQHandler,Default_Handler + + .weak EXTI8_IRQHandler + .thumb_set EXTI8_IRQHandler,Default_Handler + + .weak EXTI9_IRQHandler + .thumb_set EXTI9_IRQHandler,Default_Handler + + .weak DMA2_Stream5_IRQHandler + .thumb_set DMA2_Stream5_IRQHandler,Default_Handler + + .weak DMA2_Stream6_IRQHandler + .thumb_set DMA2_Stream6_IRQHandler,Default_Handler + + .weak DMA2_Stream7_IRQHandler + .thumb_set DMA2_Stream7_IRQHandler,Default_Handler + + .weak USART6_IRQHandler + .thumb_set USART6_IRQHandler,Default_Handler + + .weak I2C3_EV_IRQHandler + .thumb_set I2C3_EV_IRQHandler,Default_Handler + + .weak I2C3_ER_IRQHandler + .thumb_set I2C3_ER_IRQHandler,Default_Handler + + .weak USBH_OHCI_IRQHandler + .thumb_set USBH_OHCI_IRQHandler,Default_Handler + + .weak USBH_EHCI_IRQHandler + .thumb_set USBH_EHCI_IRQHandler,Default_Handler + + .weak EXTI12_IRQHandler + .thumb_set EXTI12_IRQHandler,Default_Handler + + .weak EXTI13_IRQHandler + .thumb_set EXTI13_IRQHandler,Default_Handler + + .weak DCMI_IRQHandler + .thumb_set DCMI_IRQHandler,Default_Handler + + .weak CRYP1_IRQHandler + .thumb_set CRYP1_IRQHandler,Default_Handler + + .weak HASH1_IRQHandler + .thumb_set HASH1_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 SPI5_IRQHandler + .thumb_set SPI5_IRQHandler,Default_Handler + + .weak SPI6_IRQHandler + .thumb_set SPI6_IRQHandler,Default_Handler + + .weak SAI1_IRQHandler + .thumb_set SAI1_IRQHandler,Default_Handler + + .weak LTDC_IRQHandler + .thumb_set LTDC_IRQHandler,Default_Handler + + .weak LTDC_ER_IRQHandler + .thumb_set LTDC_ER_IRQHandler,Default_Handler + + .weak SAI2_IRQHandler + .thumb_set SAI2_IRQHandler,Default_Handler + + .weak QUADSPI_IRQHandler + .thumb_set QUADSPI_IRQHandler,Default_Handler + + .weak LPTIM1_IRQHandler + .thumb_set LPTIM1_IRQHandler,Default_Handler + + .weak CEC_IRQHandler + .thumb_set CEC_IRQHandler,Default_Handler + + .weak I2C4_EV_IRQHandler + .thumb_set I2C4_EV_IRQHandler,Default_Handler + + .weak I2C4_ER_IRQHandler + .thumb_set I2C4_ER_IRQHandler,Default_Handler + + .weak SPDIF_RX_IRQHandler + .thumb_set SPDIF_RX_IRQHandler,Default_Handler + + .weak OTG_IRQHandler + .thumb_set OTG_IRQHandler,Default_Handler + + .weak IPCC_RX0_IRQHandler + .thumb_set IPCC_RX0_IRQHandler,Default_Handler + + .weak IPCC_TX0_IRQHandler + .thumb_set IPCC_TX0_IRQHandler,Default_Handler + + .weak DMAMUX1_OVR_IRQHandler + .thumb_set DMAMUX1_OVR_IRQHandler,Default_Handler + + .weak IPCC_RX1_IRQHandler + .thumb_set IPCC_RX1_IRQHandler,Default_Handler + + .weak IPCC_TX1_IRQHandler + .thumb_set IPCC_TX1_IRQHandler,Default_Handler + + .weak CRYP2_IRQHandler + .thumb_set CRYP2_IRQHandler,Default_Handler + + .weak HASH2_IRQHandler + .thumb_set HASH2_IRQHandler,Default_Handler + + .weak I2C5_EV_IRQHandler + .thumb_set I2C5_EV_IRQHandler,Default_Handler + + .weak I2C5_ER_IRQHandler + .thumb_set I2C5_ER_IRQHandler,Default_Handler + + .weak GPU_IRQHandler + .thumb_set GPU_IRQHandler,Default_Handler + + .weak DFSDM1_FLT0_IRQHandler + .thumb_set DFSDM1_FLT0_IRQHandler,Default_Handler + + .weak DFSDM1_FLT1_IRQHandler + .thumb_set DFSDM1_FLT1_IRQHandler,Default_Handler + + .weak DFSDM1_FLT2_IRQHandler + .thumb_set DFSDM1_FLT2_IRQHandler,Default_Handler + + .weak DFSDM1_FLT3_IRQHandler + .thumb_set DFSDM1_FLT3_IRQHandler,Default_Handler + + .weak SAI3_IRQHandler + .thumb_set SAI3_IRQHandler,Default_Handler + + .weak DFSDM1_FLT4_IRQHandler + .thumb_set DFSDM1_FLT4_IRQHandler,Default_Handler + + .weak TIM15_IRQHandler + .thumb_set TIM15_IRQHandler,Default_Handler + + .weak TIM16_IRQHandler + .thumb_set TIM16_IRQHandler,Default_Handler + + .weak TIM17_IRQHandler + .thumb_set TIM17_IRQHandler,Default_Handler + + .weak TIM12_IRQHandler + .thumb_set TIM12_IRQHandler,Default_Handler + + .weak MDIOS_IRQHandler + .thumb_set MDIOS_IRQHandler,Default_Handler + + .weak EXTI14_IRQHandler + .thumb_set EXTI14_IRQHandler,Default_Handler + + .weak MDMA_IRQHandler + .thumb_set MDMA_IRQHandler,Default_Handler + + .weak DSI_IRQHandler + .thumb_set DSI_IRQHandler,Default_Handler + + .weak SDMMC2_IRQHandler + .thumb_set SDMMC2_IRQHandler,Default_Handler + + .weak HSEM_IT2_IRQHandler + .thumb_set HSEM_IT2_IRQHandler,Default_Handler + + .weak DFSDM1_FLT5_IRQHandler + .thumb_set DFSDM1_FLT5_IRQHandler,Default_Handler + + .weak EXTI15_IRQHandler + .thumb_set EXTI15_IRQHandler,Default_Handler + + .weak nCTIIRQ1_IRQHandler + .thumb_set nCTIIRQ1_IRQHandler,Default_Handler + + .weak nCTIIRQ2_IRQHandler + .thumb_set nCTIIRQ2_IRQHandler,Default_Handler + + .weak TIM13_IRQHandler + .thumb_set TIM13_IRQHandler,Default_Handler + + .weak TIM14_IRQHandler + .thumb_set TIM14_IRQHandler,Default_Handler + + .weak DAC_IRQHandler + .thumb_set DAC_IRQHandler,Default_Handler + + .weak RNG1_IRQHandler + .thumb_set RNG1_IRQHandler,Default_Handler + + .weak RNG2_IRQHandler + .thumb_set RNG2_IRQHandler,Default_Handler + + .weak I2C6_EV_IRQHandler + .thumb_set I2C6_EV_IRQHandler,Default_Handler + + .weak I2C6_ER_IRQHandler + .thumb_set I2C6_ER_IRQHandler,Default_Handler + + .weak SDMMC3_IRQHandler + .thumb_set SDMMC3_IRQHandler,Default_Handler + + .weak LPTIM2_IRQHandler + .thumb_set LPTIM2_IRQHandler,Default_Handler + + .weak LPTIM3_IRQHandler + .thumb_set LPTIM3_IRQHandler,Default_Handler + + .weak LPTIM4_IRQHandler + .thumb_set LPTIM4_IRQHandler,Default_Handler + + .weak LPTIM5_IRQHandler + .thumb_set LPTIM5_IRQHandler,Default_Handler + + .weak MPU_SEV_IRQHandler + .thumb_set MPU_SEV_IRQHandler,Default_Handler + + .weak RCC_WAKEUP_IRQHandler + .thumb_set RCC_WAKEUP_IRQHandler,Default_Handler + + .weak SAI4_IRQHandler + .thumb_set SAI4_IRQHandler,Default_Handler + + .weak DTS_IRQHandler + .thumb_set DTS_IRQHandler,Default_Handler + + .weak RESERVED148_IRQHandler + .thumb_set RESERVED148_IRQHandler,Default_Handler + + .weak WAKEUP_PIN_IRQHandler + .thumb_set WAKEUP_PIN_IRQHandler,Default_Handler diff --git a/GCC/stm32mp15xx_m4.ld b/GCC/stm32mp15xx_m4.ld new file mode 100644 index 0000000..f3841e5 --- /dev/null +++ b/GCC/stm32mp15xx_m4.ld @@ -0,0 +1,200 @@ +/* +****************************************************************************** +** +** File : LinkerScript.ld +** +** Abstract : Linker script for STM32MP1 series +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** Distribution: The file is distributed “as is,” without any warranty +** of any kind. +** +***************************************************************************** +** @attention +** +** Copyright (c) 2019 STMicroelectronics. +** All rights reserved. +** +** This software is licensed under terms that can be found in the LICENSE file +** in the root directory of this software component. +** If no LICENSE file comes with this software, it is provided AS-IS. +** +****************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x10040000; /* end of RAM */ + +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Memories definition */ +MEMORY +{ + m_interrupts (RX) : ORIGIN = 0x00000000, LENGTH = 0x00000298 + m_text (RX) : ORIGIN = 0x10000000, LENGTH = 0x00020000 + m_data (RW) : ORIGIN = 0x10020000, LENGTH = 0x00020000 + m_ipc_shm (RW) : ORIGIN = 0x10040000, LENGTH = 0x00008000 +} + +/* Symbols needed for OpenAMP to enable rpmsg */ +__OPENAMP_region_start__ = ORIGIN(m_ipc_shm); +__OPENAMP_region_end__ = ORIGIN(m_ipc_shm)+LENGTH(m_ipc_shm); + +/* Sections */ +SECTIONS +{ + /* The startup code into ROM memory */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } > m_interrupts + + /* The program code and other data into ROM memory */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } > m_text + + /* Constant data into ROM memory*/ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } > m_text + + .ARM.extab : { + . = ALIGN(4); + *(.ARM.extab* .gnu.linkonce.armextab.*) + . = ALIGN(4); + } > m_text + + .ARM : { + . = ALIGN(4); + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + . = ALIGN(4); + } > m_text + + .preinit_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + . = ALIGN(4); + } > m_text + + .init_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + . = ALIGN(4); + } > m_text + + .fini_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + . = ALIGN(4); + } > m_text + + /* Used by the startup to initialize data */ + __DATA_ROM = .; + _sidata = LOADADDR(.data); + + /* Initialized data sections */ + .data : AT(__DATA_ROM) + { + . = 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 */ + } > m_data + + __DATA_END = __DATA_ROM + (_edata - _sdata); + text_end = ORIGIN(m_text) + LENGTH(m_text); + ASSERT(__DATA_END <= text_end, "region m_text overflowed with text and data") + + .resource_table : + { + . = ALIGN(4); + KEEP (*(.resource_table*)) + . = ALIGN(4); + } > m_data + _eirsc = LOADADDR(.resource_table) + SIZEOF(.resource_table); + ASSERT(SIZEOF(.resource_table) == 0 || _eirsc <= text_end, "no room for resource_table load section in text") + + /* Uninitialized data section into RAM memory */ + . = ALIGN(4); + .bss : AT (ADDR (.bss)) + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } > m_data + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } > m_data + + + /* Remove information from the compiler libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } + +} diff --git a/SDK b/SDK new file mode 160000 index 0000000..a3859ad --- /dev/null +++ b/SDK @@ -0,0 +1 @@ +Subproject commit a3859adf6b4aeb14e19fcdae7e62e98546e781fe diff --git a/arm-none-eabi.cmake b/arm-none-eabi.cmake new file mode 100644 index 0000000..a9ef74e --- /dev/null +++ b/arm-none-eabi.cmake @@ -0,0 +1,17 @@ +# Poor old Windows... +if(WIN32) + set(CMAKE_SYSTEM_NAME "Generic") +endif() + +set(CMAKE_C_COMPILER arm-none-eabi-gcc) +set(CMAKE_CXX_COMPILER arm-none-eabi-g++) + +# Optionally set size binary name, for elf section size reporting. +set(TARGET_TOOLCHAIN_SIZE arm-none-eabi-size) + +set(CMAKE_C_FLAGS_INIT "-mcpu=cortex-m7 -mthumb -mfloat-abi=hard -mfpu=fpv5-d16") +set(CMAKE_CXX_FLAGS_INIT "-mcpu=cortex-m7 -mthumb -mfloat-abi=hard -mfpu=fpv5-d16") +set(CMAKE_EXE_LINKER_FLAGS_INIT "-specs=nano.specs -specs=nosys.specs -Wl,--print-memory-usage -Wl,--no-warn-rwx-segments") + +# Make CMake happy about those compilers +set(CMAKE_TRY_COMPILE_TARGET_TYPE "STATIC_LIBRARY") diff --git a/board/board.c b/board/board.c new file mode 100644 index 0000000..f77268f --- /dev/null +++ b/board/board.c @@ -0,0 +1,10 @@ +#include "board.h" + +#include "stm32mp1xx_hal.h" + +void Error_Handler(void) { + for (;;) { + /* -- */ + asm volatile("nop"); + } +} diff --git a/board/board.h b/board/board.h new file mode 100644 index 0000000..2315095 --- /dev/null +++ b/board/board.h @@ -0,0 +1,6 @@ +#ifndef BOARD_H +#define BOARD_H + +void Error_Handler(void); + +#endif \ No newline at end of file diff --git a/board/clock_config.c b/board/clock_config.c new file mode 100644 index 0000000..e7fc7bd --- /dev/null +++ b/board/clock_config.c @@ -0,0 +1,6 @@ +#include "board.h" +#include "stm32mp1xx_hal.h" + +void BOARD_InitBootClocks(void) { + SystemCoreClockUpdate(); +} diff --git a/board/clock_config.h b/board/clock_config.h new file mode 100644 index 0000000..b62d9bf --- /dev/null +++ b/board/clock_config.h @@ -0,0 +1,6 @@ +#ifndef CLOCK_CONFIG_H +#define CLOCK_CONFIG_H + +void BOARD_InitBootClocks(void); + +#endif \ No newline at end of file diff --git a/board/peripherals.c b/board/peripherals.c new file mode 100644 index 0000000..3d52f59 --- /dev/null +++ b/board/peripherals.c @@ -0,0 +1,10 @@ +#include "peripherals.h" + +#include "board.h" + +void BOARD_InitBootPeripherals(void) { + BOARD_InitDebugUART(); +} + +void BOARD_InitDebugUART(void) { +} \ No newline at end of file diff --git a/board/peripherals.h b/board/peripherals.h new file mode 100644 index 0000000..20304df --- /dev/null +++ b/board/peripherals.h @@ -0,0 +1,9 @@ +#ifndef PERIPHERALS_H +#define PERIPHERALS_H + +#include "stm32mp1xx_hal.h" + +void BOARD_InitBootPeripherals(void); +void BOARD_InitDebugUART(void); + +#endif diff --git a/board/pin_mux.c b/board/pin_mux.c new file mode 100644 index 0000000..8e52de6 --- /dev/null +++ b/board/pin_mux.c @@ -0,0 +1,6 @@ +#include "pin_mux.h" + +#include "stm32mp1xx_hal.h" + +void BOARD_InitBootPins(void) { +} \ No newline at end of file diff --git a/board/pin_mux.h b/board/pin_mux.h new file mode 100644 index 0000000..e21d7c0 --- /dev/null +++ b/board/pin_mux.h @@ -0,0 +1,6 @@ +#ifndef PIN_MUX_H +#define PIN_MUX_H + +void BOARD_InitBootPins(); + +#endif \ No newline at end of file diff --git a/board/stm32mp1xx_hal_conf.h b/board/stm32mp1xx_hal_conf.h new file mode 100644 index 0000000..b5f74c2 --- /dev/null +++ b/board/stm32mp1xx_hal_conf.h @@ -0,0 +1,387 @@ +/** + ****************************************************************************** + * @file stm32mp1xx_hal_conf.h + * @author MCD Application Team + * @brief HAL configuration template file. + * This file should be copied to the application folder and renamed + * to stm32mp1xx_hal_conf.h. + ****************************************************************************** + * + * @attention + * + * Copyright (c) 2021 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32MP1xx_HAL_CONF_H +#define __STM32MP1xx_HAL_CONF_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* ########################## Module Selection ############################## */ +/** + * @brief This is the list of modules to be used in the HAL driver + */ +#define HAL_MODULE_ENABLED +/*#define HAL_ADC_MODULE_ENABLED */ +/*#define HAL_CEC_MODULE_ENABLED */ +/*#define HAL_CRC_MODULE_ENABLED */ +/*#define HAL_CRYP_MODULE_ENABLED */ +/*#define HAL_DAC_MODULE_ENABLED */ +/*#define HAL_DCMI_MODULE_ENABLED */ +/*#define HAL_DSI_MODULE_ENABLED */ +/*#define HAL_DFSDM_MODULE_ENABLED */ +/*#define HAL_ETH_MODULE_ENABLED */ +/*#define HAL_FDCAN_MODULE_ENABLED */ +/*#define HAL_HASH_MODULE_ENABLED */ +/*#define HAL_HCD_MODULE_ENABLED */ +/*#define HAL_I2C_MODULE_ENABLED */ +/*#define HAL_I2S_MODULE_ENABLED */ +/*#define HAL_IPCC_MODULE_ENABLED */ +/*#define HAL_IWDG_MODULE_ENABLED */ +/*#define HAL_LPTIM_MODULE_ENABLED */ +/*#define HAL_LTDC_MODULE_ENABLED */ +/*#define HAL_NAND_MODULE_ENABLED */ +/*#define HAL_NOR_MODULE_ENABLED */ +/*#define HAL_PCD_MODULE_ENABLED */ +/*#define HAL_QSPI_MODULE_ENABLED */ +/*#define HAL_RNG_MODULE_ENABLED */ +/*#define HAL_SAI_MODULE_ENABLED */ +/*#define HAL_SD_MODULE_ENABLED */ +/*#define HAL_MMC_MODULE_ENABLED */ +/*#define HAL_RTC_MODULE_ENABLED */ +/*#define HAL_SMBUS_MODULE_ENABLED */ +/*#define HAL_SPDIFRX_MODULE_ENABLED */ +/*#define HAL_SPI_MODULE_ENABLED */ +/*#define HAL_SRAM_MODULE_ENABLED */ +/*#define HAL_TAMP_MODULE_ENABLED */ +/*#define HAL_TIM_MODULE_ENABLED */ +/*#define HAL_TMPSENS_MODULE_ENABLED */ +#define HAL_UART_MODULE_ENABLED +/*#define HAL_USART_MODULE_ENABLED */ +/*#define HAL_WWDG_MODULE_ENABLED */ +#define HAL_EXTI_MODULE_ENABLED +#define HAL_HSEM_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +/*#define HAL_MDMA_MODULE_ENABLED */ +#define HAL_RCC_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED + +/* ########################## Oscillator Values adaptation ####################*/ +/** + * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSE is used as system clock source, directly or through the PLL). + */ +#if !defined (HSE_VALUE) +#define HSE_VALUE ((uint32_t)24000000) /*!< Value of the External oscillator in Hz : FPGA case fixed to 60MHZ */ +#endif /* HSE_VALUE */ + +#if !defined (HSE_STARTUP_TIMEOUT) + #define HSE_STARTUP_TIMEOUT ((uint32_t)100U) /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal High Speed oscillator (HSI) value. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSI is used as system clock source, directly or through the PLL). + */ +#if !defined (HSI_VALUE) + #define HSI_VALUE ((uint32_t)64000000) /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#if !defined (LSI_VALUE) + #define LSI_VALUE 32000U +#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz + The real value may vary depending on the variations + in voltage and temperature. */ + +/** + * @brief External Low Speed oscillator (LSE) value. + * This value is used by the UART, RTC HAL module to compute the system frequency + */ +#if !defined (LSE_VALUE) + #define LSE_VALUE ((uint32_t)32768U) /*!< Value of the External oscillator in Hz*/ +#endif /* LSE_VALUE */ + +#if !defined (LSE_STARTUP_TIMEOUT) + #define LSE_STARTUP_TIMEOUT ((uint32_t)5000U) /*!< Time out for LSE start up, in ms */ +#endif /* LSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal oscillator (CSI) default value. + * This value is the default CSI value after Reset. + */ +#if !defined (CSI_VALUE) + #define CSI_VALUE 4000000U /*!< Value of the Internal oscillator in Hz*/ +#endif /* CSI_VALUE */ + +/** + * @brief External clock source for I2S peripheral + * This value is used by the I2S HAL module to compute the I2S clock source + * frequency, this source is inserted directly through I2S_CKIN pad. + */ +#if !defined (EXTERNAL_CLOCK_VALUE) + #define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External clock in Hz*/ +#endif /* EXTERNAL_CLOCK_VALUE */ + +/* Tip: To avoid modifying this file each time you need to use different HSE, + === you can define the HSE value in your toolchain compiler preprocessor. */ + +/* ########################### System Configuration ######################### */ +/** + * @brief This is the HAL system configuration section + */ +#define VDD_VALUE 3300U /*!< Value of VDD in mv */ +#define TICK_INT_PRIORITY 0x0FU /*!< tick interrupt priority */ +#define USE_RTOS 0U + +#define PREFETCH_ENABLE 0U +#define INSTRUCTION_CACHE_ENABLE 0U +#define DATA_CACHE_ENABLE 0U + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ +/* #define USE_FULL_ASSERT 1U */ + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED + #include "stm32mp1xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_EXTI_MODULE_ENABLED + #include "stm32mp1xx_hal_exti.h" +#endif /* HAL_EXTI_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED + #include "stm32mp1xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_HSEM_MODULE_ENABLED + #include "stm32mp1xx_hal_hsem.h" +#endif /* HAL_HSEM_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED + #include "stm32mp1xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_MDMA_MODULE_ENABLED + #include "stm32mp1xx_hal_mdma.h" +#endif /* HAL_MDMA_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + #include "stm32mp1xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED + #include "stm32mp1xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CEC_MODULE_ENABLED + #include "stm32mp1xx_hal_cec.h" +#endif /* HAL_CEC_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED + #include "stm32mp1xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED + #include "stm32mp1xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED + #include "stm32mp1xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_DCMI_MODULE_ENABLED + #include "stm32mp1xx_hal_dcmi.h" +#endif /* HAL_DCMI_MODULE_ENABLED */ + +#ifdef HAL_DFSDM_MODULE_ENABLED + #include "stm32mp1xx_hal_dfsdm.h" +#endif /* HAL_DFSDM_MODULE_ENABLED */ + +#ifdef HAL_DSI_MODULE_ENABLED + #include "stm32mp1xx_hal_dsi.h" +#endif /* HAL_DSI_MODULE_ENABLED */ + +#ifdef HAL_ETH_MODULE_ENABLED + #include "stm32mp1xx_hal_eth.h" +#endif /* HAL_ETH_MODULE_ENABLED */ + +#ifdef HAL_EXTI_MODULE_ENABLED + #include "stm32mp1xx_hal_exti.h" +#endif /* HAL_EXTI_MODULE_ENABLED */ + +#ifdef HAL_FDCAN_MODULE_ENABLED + #include "stm32mp1xx_hal_fdcan.h" +#endif /* HAL_FDCAN_MODULE_ENABLED */ + +#ifdef HAL_HASH_MODULE_ENABLED + #include "stm32mp1xx_hal_hash.h" +#endif /* HAL_HASH_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED + #include "stm32mp1xx_hal_hcd.h" +#endif /* HAL_HASH_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED + #include "stm32mp1xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED + #include "stm32mp1xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IPCC_MODULE_ENABLED + #include "stm32mp1xx_hal_ipcc.h" +#endif /* HAL_IPCC_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "stm32mp1xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "stm32mp1xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_LPTIM_MODULE_ENABLED + #include "stm32mp1xx_hal_lptim.h" +#endif /* HAL_LPTIM_MODULE_ENABLED */ + +#ifdef HAL_LTDC_MODULE_ENABLED + #include "stm32mp1xx_hal_ltdc.h" +#endif /* HAL_LTDC_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED + #include "stm32mp1xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED + #include "stm32mp1xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED + #include "stm32mp1xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED + #include "stm32mp1xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_QSPI_MODULE_ENABLED + #include "stm32mp1xx_hal_qspi.h" +#endif /* HAL_QSPI_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED + #include "stm32mp1xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_SAI_MODULE_ENABLED + #include "stm32mp1xx_hal_sai.h" +#endif /* HAL_SAI_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED + #include "stm32mp1xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_MMC_MODULE_ENABLED + #include "stm32mp1xx_hal_mmc.h" +#endif /* HAL_MMC_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED + #include "stm32mp1xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_SMBUS_MODULE_ENABLED + #include "stm32mp1xx_hal_smbus.h" +#endif /* HAL_SMBUS_MODULE_ENABLED */ + +#ifdef HAL_SPDIFRX_MODULE_ENABLED + #include "stm32mp1xx_hal_spdifrx.h" +#endif /* HAL_SPDIFRX_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED + #include "stm32mp1xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED + #include "stm32mp1xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED + #include "stm32mp1xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_TAMP_MODULE_ENABLED + #include "stm32mp1xx_hal_tamp.h" +#endif /* HAL_TAMP_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED + #include "stm32mp1xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_TMPSENS_MODULE_ENABLED + #include "stm32mp1xx_hal_tmpsens.h" +#endif /* HAL_TMPSENS_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED + #include "stm32mp1xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED + #include "stm32mp1xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED + #include "stm32mp1xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t* file, uint32_t line); +#else + #define assert_param(expr) ((void)0) +#endif /* USE_FULL_ASSERT */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32MP1xx_HAL_CONF_H */ + diff --git a/board/stm32mp1xx_it.c b/board/stm32mp1xx_it.c new file mode 100644 index 0000000..6d92ddc --- /dev/null +++ b/board/stm32mp1xx_it.c @@ -0,0 +1,203 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file Templates/Src/stm32mp1xx_it.c + * @author MCD Application Team + * @brief Main Interrupt Service Routines. + * This file provides template for all exceptions handler and + * peripherals interrupt service routine. + ****************************************************************************** + * @attention + * + * Copyright (c) 2021 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32mp1xx_hal.h" +#include "stm32mp1xx_it.h" +/* Private includes ----------------------------------------------------------*/ +/* USER CODE BEGIN Includes */ +/* USER CODE END Includes */ + +/* Private typedef -----------------------------------------------------------*/ +/* USER CODE BEGIN TD */ + +/* USER CODE END TD */ + +/* Private define ------------------------------------------------------------*/ +/* USER CODE BEGIN PD */ + +/* USER CODE END PD */ + +/* Private macro -------------------------------------------------------------*/ +/* USER CODE BEGIN PM */ + +/* USER CODE END PM */ + +/* Private variables ---------------------------------------------------------*/ +/* USER CODE BEGIN PV */ + +/* USER CODE END PV */ + +/* Private function prototypes -----------------------------------------------*/ +/* USER CODE BEGIN PFP */ + +/* USER CODE END PFP */ + +/* Private user code ---------------------------------------------------------*/ +/* USER CODE BEGIN 0 */ + +/* USER CODE END 0 */ + +/* External variables --------------------------------------------------------*/ +/* USER CODE BEGIN EV */ + +/* USER CODE END EV */ + +/******************************************************************************/ +/* Cortex Processor Interruption and Exception Handlers */ +/******************************************************************************/ +/** + * @brief This function handles Non maskable interrupt. + */ +void NMI_Handler(void) +{ + /* USER CODE BEGIN NonMaskableInt_IRQn 0 */ + + /* USER CODE END NonMaskableInt_IRQn 0 */ + /* USER CODE BEGIN NonMaskableInt_IRQn 1 */ + + /* USER CODE END NonMaskableInt_IRQn 1 */ +} + +/** + * @brief This function handles Hard fault interrupt. + */ +void HardFault_Handler(void) +{ + /* USER CODE BEGIN HardFault_IRQn 0 */ + + /* USER CODE END HardFault_IRQn 0 */ + while (1) + { + /* USER CODE BEGIN W1_HardFault_IRQn 0 */ + /* USER CODE END W1_HardFault_IRQn 0 */ + } +} + +/** + * @brief This function handles Memory management fault. + */ +void MemManage_Handler(void) +{ + /* USER CODE BEGIN MemoryManagement_IRQn 0 */ + + /* USER CODE END MemoryManagement_IRQn 0 */ + while (1) + { + /* USER CODE BEGIN W1_MemoryManagement_IRQn 0 */ + /* USER CODE END W1_MemoryManagement_IRQn 0 */ + } +} + +/** + * @brief This function handles Pre-fetch fault, memory access fault. + */ +void BusFault_Handler(void) +{ + /* USER CODE BEGIN BusFault_IRQn 0 */ + + /* USER CODE END BusFault_IRQn 0 */ + while (1) + { + /* USER CODE BEGIN W1_BusFault_IRQn 0 */ + /* USER CODE END W1_BusFault_IRQn 0 */ + } +} + +/** + * @brief This function handles Undefined instruction or illegal state. + */ +void UsageFault_Handler(void) +{ + /* USER CODE BEGIN UsageFault_IRQn 0 */ + + /* USER CODE END UsageFault_IRQn 0 */ + while (1) + { + /* USER CODE BEGIN W1_UsageFault_IRQn 0 */ + /* USER CODE END W1_UsageFault_IRQn 0 */ + } +} + +/** + * @brief This function handles System service call via SWI instruction. + */ +void SVC_Handler(void) +{ + /* USER CODE BEGIN SVCall_IRQn 0 */ + + /* USER CODE END SVCall_IRQn 0 */ + /* USER CODE BEGIN SVCall_IRQn 1 */ + + /* USER CODE END SVCall_IRQn 1 */ +} + +/** + * @brief This function handles Debug monitor. + */ +void DebugMon_Handler(void) +{ + /* USER CODE BEGIN DebugMonitor_IRQn 0 */ + + /* USER CODE END DebugMonitor_IRQn 0 */ + /* USER CODE BEGIN DebugMonitor_IRQn 1 */ + + /* USER CODE END DebugMonitor_IRQn 1 */ +} + +/** + * @brief This function handles Pendable request for system service. + */ +void PendSV_Handler(void) +{ + /* USER CODE BEGIN PendSV_IRQn 0 */ + + /* USER CODE END PendSV_IRQn 0 */ + /* USER CODE BEGIN PendSV_IRQn 1 */ + + /* USER CODE END PendSV_IRQn 1 */ +} + +/** + * @brief This function handles System tick timer. + */ +void SysTick_Handler(void) +{ + /* USER CODE BEGIN SysTick_IRQn 0 */ + + /* USER CODE END SysTick_IRQn 0 */ + HAL_IncTick(); + /* USER CODE BEGIN SysTick_IRQn 1 */ + + /* USER CODE END SysTick_IRQn 1 */ +} + +/******************************************************************************/ +/* STM32MP1xx Peripheral Interrupt Handlers */ +/* Add here the Interrupt Handlers for the used peripherals. */ +/* For the available peripheral interrupt handler names, */ +/* please refer to the startup file (startup_stm32mp1xx.s). */ +/******************************************************************************/ + +/* USER CODE BEGIN 1 */ + +/* USER CODE END 1 */ diff --git a/board/stm32mp1xx_it.h b/board/stm32mp1xx_it.h new file mode 100644 index 0000000..fd84587 --- /dev/null +++ b/board/stm32mp1xx_it.h @@ -0,0 +1,68 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file Templates/Inc/stm32mp1xx_it.h + * @author MCD Application Team + * @brief This file contains the headers of the interrupt handlers. + ****************************************************************************** + * @attention + * + * Copyright (c) 2021 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32MP1xx_IT_H +#define __STM32MP1xx_IT_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Private includes ----------------------------------------------------------*/ +/* USER CODE BEGIN Includes */ + +/* USER CODE END Includes */ + +/* Exported types ------------------------------------------------------------*/ +/* USER CODE BEGIN ET */ + +/* USER CODE END ET */ + +/* Exported constants --------------------------------------------------------*/ +/* USER CODE BEGIN EC */ + +/* USER CODE END EC */ + +/* Exported macro ------------------------------------------------------------*/ +/* USER CODE BEGIN EM */ + +/* USER CODE END EM */ + +/* Exported functions prototypes ---------------------------------------------*/ +void NMI_Handler(void); +void HardFault_Handler(void); +void MemManage_Handler(void); +void BusFault_Handler(void); +void UsageFault_Handler(void); +void SVC_Handler(void); +void DebugMon_Handler(void); +void PendSV_Handler(void); +void SysTick_Handler(void); +/* USER CODE BEGIN EFP */ + +/* USER CODE END EFP */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32MP1xx_IT_H */ + diff --git a/board/system_stm32mp1xx.c b/board/system_stm32mp1xx.c new file mode 100644 index 0000000..305da4f --- /dev/null +++ b/board/system_stm32mp1xx.c @@ -0,0 +1,286 @@ +/** + ****************************************************************************** + * @file system_stm32mp1xx.c + * @author MCD Application Team + * @brief CMSIS Cortex Device Peripheral Access Layer System Source File. + * + * This file provides two functions and one global variable to be called from + * user application: + * - SystemInit(): This function is called at startup just after reset and + * before branch to main program. This call is made inside + * the "startup_stm32mp1xx.s" file. + * + * - SystemCoreClock variable: Contains the core clock frequency, it can + * be used by the user application to setup + * the SysTick timer or configure other + * parameters. + * + * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must + * be called whenever the core clock is changed + * during program execution. + * + * + ****************************************************************************** + * @attention + * + * Copyright (c) 2021 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32mp1xx_system + * @{ + */ + +/** @addtogroup STM32MP1xx_System_Private_Includes + * @{ + */ + +#include "stm32mp1xx.h" + +/** + * @} + */ + +/** @addtogroup STM32MP1xx_System_Private_TypesDefinitions + * @{ + */ + + +/** + * @} + */ + +/** @addtogroup STM32MP1xx_System_Private_Defines + * @{ + */ + + +/************************* Miscellaneous Configuration ************************/ +/*!< Uncomment the following line if you need to use external SRAM mounted + on EVAL board as data memory */ +/* #define DATA_IN_ExtSRAM */ + +/*!< Uncomment the following line if you need to relocate your vector Table in + Internal SRAM. */ +/* #define VECT_TAB_SRAM */ +#define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field. + This value must be a multiple of 0x200. */ +/******************************************************************************/ + +/** + * @} + */ + +/** @addtogroup STM32MP1xx_System_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32MP1xx_System_Private_Variables + * @{ + */ + /* This variable is updated in three ways: + 1) by calling CMSIS function SystemCoreClockUpdate() + 2) each time HAL_RCC_ClockConfig() is called to configure the system clock + frequency + Note: If you use this function to configure the system clock; + then there is no need to call the first functions listed above, + since SystemCoreClock variable is updated automatically. + */ + uint32_t SystemCoreClock = HSI_VALUE; +/** + * @} + */ + +/** @addtogroup STM32MP1xx_System_Private_FunctionPrototypes + * @{ + */ + +#if defined (DATA_IN_ExtSRAM) + static void SystemInit_ExtMemCtl(void); +#endif /* DATA_IN_ExtSRAM */ + +/** + * @} + */ + +/** @addtogroup STM32MP1xx_System_Private_Functions + * @{ + */ + + /** + * @brief Setup the microcontroller system + * Initialize the FPU setting, vector table location and External memory + * configuration. + * @param None + * @retval None + */ +void SystemInit (void) +{ + /* FPU settings ------------------------------------------------------------*/ +#if defined (CORE_CM4) + #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */ + #endif + + /* Configure the Vector Table location add offset address ------------------*/ +#if defined (VECT_TAB_SRAM) + SCB->VTOR = MCU_AHB_SRAM | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */ +#endif + /* Disable all interrupts and events */ + CLEAR_REG(EXTI_C2->IMR1); + CLEAR_REG(EXTI_C2->IMR2); + CLEAR_REG(EXTI_C2->IMR3); + CLEAR_REG(EXTI_C2->EMR1); + CLEAR_REG(EXTI_C2->EMR2); + CLEAR_REG(EXTI_C2->EMR3); +#else +#error Please #define CORE_CM4 +#endif +} + +/** + * @brief Update SystemCoreClock variable according to Clock Register Values. + * The SystemCoreClock variable contains the core clock frequency (Hz), + * it can be used by the user application to setup the SysTick timer or + * configure other parameters. + * + * @note Each time the core clock changes, this function must be called to + * update SystemCoreClock variable value. Otherwise, any configuration + * based on this variable will be incorrect. + * + * @note - The system frequency computed by this function is not the real + * frequency in the chip. It is calculated based on the predefined + * constant and the selected clock source: + * + * - If SYSCLK source is HSI, SystemCoreClock will contain the + * HSI_VALUE(*) + * + * - If SYSCLK source is HSE, SystemCoreClock will contain the + * HSE_VALUE(**) + * + * - If SYSCLK source is CSI, SystemCoreClock will contain the + * CSI_VALUE(***) + * + * - If SYSCLK source is PLL3_P, SystemCoreClock will contain the + * HSI_VALUE(*) or the HSE_VALUE(*) or the CSI_VALUE(***) + * multiplied/divided by the PLL3 factors. + * + * (*) HSI_VALUE is a constant defined in stm32mp1xx_hal_conf.h file + * (default value 64 MHz) but the real value may vary depending + * on the variations in voltage and temperature. + * + * (**) HSE_VALUE is a constant defined in stm32mp1xx_hal_conf.h file + * (default value 24 MHz), user has to ensure that HSE_VALUE is + * same as the real frequency of the crystal used. Otherwise, this + * function may have wrong result. + * + * (***) CSI_VALUE is a constant defined in stm32mp1xx_hal_conf.h file + * (default value 4 MHz)but the real value may vary depending + * on the variations in voltage and temperature. + * + * - The result of this function could be not correct when using + * fractional value for HSE crystal. + * + * @param None + * @retval None + */ +void SystemCoreClockUpdate (void) +{ + uint32_t pllsource, pll3m, pll3fracen; + float fracn1, pll3vco; + + switch (RCC->MSSCKSELR & RCC_MSSCKSELR_MCUSSRC) + { + case 0x00: /* HSI used as system clock source */ + SystemCoreClock = (HSI_VALUE >> (RCC->HSICFGR & RCC_HSICFGR_HSIDIV)); + break; + + case 0x01: /* HSE used as system clock source */ + SystemCoreClock = HSE_VALUE; + break; + + case 0x02: /* CSI used as system clock source */ + SystemCoreClock = CSI_VALUE; + break; + + case 0x03: /* PLL3_P used as system clock source */ + pllsource = (RCC->RCK3SELR & RCC_RCK3SELR_PLL3SRC); + pll3m = ((RCC->PLL3CFGR1 & RCC_PLL3CFGR1_DIVM3) >> RCC_PLL3CFGR1_DIVM3_Pos) + 1U; + pll3fracen = (RCC->PLL3FRACR & RCC_PLL3FRACR_FRACLE) >> 16U; + fracn1 = (float)(pll3fracen * ((RCC->PLL3FRACR & RCC_PLL3FRACR_FRACV) >> 3U)); + pll3vco = (float)((float)((RCC->PLL3CFGR1 & RCC_PLL3CFGR1_DIVN) + 1U) + (fracn1/(float) 0x1FFFU)); + + if (pll3m != 0U) + { + switch (pllsource) + { + case 0x00: /* HSI used as PLL clock source */ + pll3vco *= (float)((HSI_VALUE >> (RCC->HSICFGR & RCC_HSICFGR_HSIDIV)) / pll3m); + break; + + case 0x01: /* HSE used as PLL clock source */ + pll3vco *= (float)(HSE_VALUE / pll3m); + break; + + case 0x02: /* CSI used as PLL clock source */ + pll3vco *= (float)(CSI_VALUE / pll3m); + break; + + case 0x03: /* No clock source for PLL */ + pll3vco = 0; + break; + } + SystemCoreClock = (uint32_t)(pll3vco/ ((float)((RCC->PLL3CFGR2 & RCC_PLL3CFGR2_DIVP) + 1U))); + } + else + { + SystemCoreClock = 0U; + } + break; + } + + /* Compute mcu_ck */ + SystemCoreClock = SystemCoreClock >> (RCC->MCUDIVR & RCC_MCUDIVR_MCUDIV); +} + + +#ifdef DATA_IN_ExtSRAM +/** + * @brief Setup the external memory controller. + * Called in startup_stm32L4xx.s before jump to main. + * This function configures the external SRAM mounted on Eval boards + * This SRAM will be used as program data memory (including heap and stack). + * @param None + * @retval None + */ +void SystemInit_ExtMemCtl(void) +{ + +} +#endif /* DATA_IN_ExtSRAM */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/src/main.c b/src/main.c new file mode 100644 index 0000000..a3d6cb0 --- /dev/null +++ b/src/main.c @@ -0,0 +1,21 @@ +#include + +/* Board */ +#include "board.h" +#include "clock_config.h" +#include "peripherals.h" +#include "pin_mux.h" + +int main(void) { + HAL_Init(); + + BOARD_InitBootClocks(); + BOARD_InitBootPins(); + BOARD_InitBootPeripherals(); + + printf("Hello world!\r\n"); + + for (;;) { + HAL_Delay(500); + } +} \ No newline at end of file diff --git a/src/syscalls.c b/src/syscalls.c new file mode 100644 index 0000000..5fee8f3 --- /dev/null +++ b/src/syscalls.c @@ -0,0 +1,5 @@ +#include "peripherals.h" + +int _write(int file, char *ptr, int len) { + return len; +} \ No newline at end of file