diff --git a/.changesets/refactor-linker-script.md b/.changesets/refactor-linker-script.md new file mode 100644 index 000000000..ffba2faf8 --- /dev/null +++ b/.changesets/refactor-linker-script.md @@ -0,0 +1,36 @@ +release: major +summary: Refactor linker script, startup code, and memory model with unified copy/zero tables, configurable ITCM, and weak BoardInit + +## Implemented + +### Linker Script (`LinkerScript.ld`) +- **Unified copy table**: all initialized data sections (ISR vector, ITCM code, `.data`, `.dtcm_rodata`, D1/D2/D3 NC and cached data/rodata) are copied from FLASH to RAM by a single generic loop in `Reset_Handler`. No more hand-written copy per section. +- **Unified zero table**: all BSS sections (DTCM `.bss`, D1/D2/D3 NC and cached BSS) are zero-initialized by the same generic mechanism. +- **Configurable ITCM**: `__ITCM_SIZE` and `__ITCM_BUILD` macros (passed via C preprocessor `-D` at build time) control ITCM size and whether `.text` is placed in ITCM instead of FLASH. +- **ISR vector always in ITCM**: the interrupt vector table is unconditionally placed in ITCMRAM and copied at startup. +- **DTCM constants**: `.dtcm_rodata` section for constants explicitly placed in DTCM (via `DTCM_RODATA` / `DTCM_RODATA_INLINE` macros), initialized from FLASH by the copy table. +- **Initialized data for all memory domains**: D1, D2, D3 each have non-cached and cached data/rodata sections (`>RAM_Dx AT> FLASH`) copied by the copy table. +- **Null-pointer guard**: 32-byte MPU region at `0x00000000` (NO_ACCESS) catches runtime null dereferences. Vector table relocated to a 1024-byte aligned location after the 32 security bytes, loaded in VTOR via `.null_guard` NOLOAD section. Region 12 > region 11 → takes priority. +- **LMA collision guard**: `BYTE(0)` in every `AT> FLASH` section prevents empty sections from clustering at the same PhysAddr, suppressing STM32_Programmer "overlapping segments" warnings. + +### Startup Code (`StartupCode.s`) +- Replaced per-section manual copy with generic copy-table loop (`__copy_table_start` → `__copy_table_end`). +- Replaced per-section manual BSS zeroing with generic zero-table loop (`__zero_table_start` → `__zero_table_end`). +- Removed `Reset_Handler` reliance on hardcoded section symbols; everything is table-driven. +- Calls `weak BoardInit()` between `SystemInit` and global constructors, allowing early hardware initialization from C++. + +### System / Board Init (`System.c`) +- Moved from template-project to ST-LIB so all projects benefit. +- Provides `weak BoardInit()` and `weak ConfigurationChecker()` — user overrides in firmware. + +### MPU (`MPU.hpp`) +- Fixed `MPUDomain::Instance::as()` and `construct()`: `Request::e` → `Target.e` for valid constexpr member access. +- Fixed `static_assert` logic: `is_nc && volatile` → `!is_nc || volatile` (cached buffers no longer trigger the assert). +- Added null-pointer guard region (region 12, `0x00000000`, 32 bytes, NO_ACCESS). +- Inline specifiers for all `*_INLINE` macros (since inline things are placed in special COMDAT sections that must be separate one from another and everything else). + +## Not implemented (left as weak symbols) +- `ConfigurationChecker`: a function to validate ITCM size and other build-time configuration at runtime. User can define it to add custom startup checks. + +## Migration guide (template-project) +The corresponding template-project PR adapts `BoardInit` to the new weak function contract, and changes the CMAKE as needed. See the template-project for details. diff --git a/CMakeLists.txt b/CMakeLists.txt index f4d629e3e..429c11200 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -414,6 +414,7 @@ add_library(${STLIB_LIBRARY} OBJECT $<$,$>:${HALAL_C_ETH_PHY}> + $<$:${CMAKE_CURRENT_LIST_DIR}/System.c> $<$:${CPP_UTILITIES_C}> $<$:${CPP_UTILITIES_CPP}> diff --git a/Inc/HALAL/Models/MPU.hpp b/Inc/HALAL/Models/MPU.hpp index 96245fff5..3a4a70883 100644 --- a/Inc/HALAL/Models/MPU.hpp +++ b/Inc/HALAL/Models/MPU.hpp @@ -41,51 +41,173 @@ #include "stm32h7xx_hal.h" #include "HALAL/Models/MPUManager/MPUManager.hpp" -// Defines for attributes -// Note1: Variables declared with these attributes will likely not be initialized by the startup -// Note2: These attributes can only be used for static/global variables #ifdef SIM_ON -#define D1_NC -#define D2_NC -#define D3_NC -#define D1_C -#define D2_C -#define D3_C + +#define D1_NC_DATA +#define D1_NC_BSS +#define D1_NC_RODATA +#define D1_NC_DATA_INLINE(name) inline +#define D1_NC_BSS_INLINE(name) inline +#define D1_NC_RODATA_INLINE(name) inline +#define D2_NC_DATA +#define D2_NC_BSS +#define D2_NC_RODATA +#define D2_NC_DATA_INLINE(name) inline +#define D2_NC_BSS_INLINE(name) inline +#define D2_NC_RODATA_INLINE(name) inline +#define D3_NC_DATA +#define D3_NC_BSS +#define D3_NC_RODATA +#define D3_NC_DATA_INLINE(name) inline +#define D3_NC_BSS_INLINE(name) inline +#define D3_NC_RODATA_INLINE(name) inline +#define D1_C_DATA +#define D1_C_BSS +#define D1_C_RODATA +#define D1_C_DATA_INLINE(name) inline +#define D1_C_BSS_INLINE(name) inline +#define D1_C_RODATA_INLINE(name) inline +#define D2_C_DATA +#define D2_C_BSS +#define D2_C_RODATA +#define D2_C_DATA_INLINE(name) inline +#define D2_C_BSS_INLINE(name) inline +#define D2_C_RODATA_INLINE(name) inline +#define D3_C_DATA +#define D3_C_BSS +#define D3_C_RODATA +#define D3_C_DATA_INLINE(name) inline +#define D3_C_BSS_INLINE(name) inline +#define D3_C_RODATA_INLINE(name) inline #define RAM_CODE +#define RAM_CODE_INLINE(name) inline +#define DTCM_RODATA +#define DTCM_RODATA_INLINE(name) inline + #else -#define D1_NC __attribute__((section(".mpu_ram_d1_nc.user"), used)) volatile -#define D2_NC __attribute__((section(".mpu_ram_d2_nc.user"), used)) volatile -#define D3_NC __attribute__((section(".mpu_ram_d3_nc.user"), used)) volatile -#define D1_C __attribute__((section(".ram_d1.user"), used)) -#define D2_C __attribute__((section(".ram_d2.user"), used)) -#define D3_C __attribute__((section(".ram_d3.user"), used)) +#define MPU_STR2(x) #x +#define MPU_STR(x) MPU_STR2(x) +#define MPU_SECTION_WITH_NAME(base, name) base "." MPU_STR(name) + +// Initialized data in non-cached D1 RAM +#define D1_NC_DATA __attribute__((section(".ram_d1_nc.user.data"))) volatile +// Uninitialized data in non-cached D1 RAM +#define D1_NC_BSS __attribute__((section(".ram_d1_nc.user.bss"))) volatile +// Read-only data in non-cached D1 RAM (mainly for rx buffers) @note Not protected by MPU +#define D1_NC_RODATA __attribute__((section(".ram_d1_nc.user.rodata"))) const volatile +#define D1_NC_DATA_INLINE(name) \ + inline __attribute__((section(MPU_SECTION_WITH_NAME(".ram_d1_nc.user.data", name)))) volatile +#define D1_NC_BSS_INLINE(name) \ + inline __attribute__((section(MPU_SECTION_WITH_NAME(".ram_d1_nc.user.bss", name)))) volatile +#define D1_NC_RODATA_INLINE(name) \ + inline __attribute__((section(MPU_SECTION_WITH_NAME(".ram_d1_nc.user.rodata", name)))) \ + const volatile +// Initialized data in non-cached D2 RAM +#define D2_NC_DATA __attribute__((section(".ram_d2_nc.user.data"))) volatile +// Uninitialized data in non-cached D2 RAM +#define D2_NC_BSS __attribute__((section(".ram_d2_nc.user.bss"))) volatile +// Read-only data in non-cached D2 RAM (mainly for rx buffers) @note Not protected by MPU +#define D2_NC_RODATA __attribute__((section(".ram_d2_nc.user.rodata"))) const volatile +#define D2_NC_DATA_INLINE(name) \ + inline __attribute__((section(MPU_SECTION_WITH_NAME(".ram_d2_nc.user.data", name)))) volatile +#define D2_NC_BSS_INLINE(name) \ + inline __attribute__((section(MPU_SECTION_WITH_NAME(".ram_d2_nc.user.bss", name)))) volatile +#define D2_NC_RODATA_INLINE(name) \ + inline __attribute__((section(MPU_SECTION_WITH_NAME(".ram_d2_nc.user.rodata", name)))) \ + const volatile +// Initialized data in non-cached D3 RAM +#define D3_NC_DATA __attribute__((section(".ram_d3_nc.user.data"))) volatile +// Uninitialized data in non-cached D3 RAM +#define D3_NC_BSS __attribute__((section(".ram_d3_nc.user.bss"))) volatile +// Read-only data in non-cached D3 RAM (mainly for rx buffers) @note Not protected by MPU +#define D3_NC_RODATA __attribute__((section(".ram_d3_nc.user.rodata"))) const volatile +#define D3_NC_DATA_INLINE(name) \ + inline __attribute__((section(MPU_SECTION_WITH_NAME(".ram_d3_nc.user.data", name)))) volatile +#define D3_NC_BSS_INLINE(name) \ + inline __attribute__((section(MPU_SECTION_WITH_NAME(".ram_d3_nc.user.bss", name)))) volatile +#define D3_NC_RODATA_INLINE(name) \ + inline __attribute__((section(MPU_SECTION_WITH_NAME(".ram_d3_nc.user.rodata", name)))) \ + const volatile +// Initialized data in cached D1 RAM +#define D1_C_DATA __attribute__((section(".ram_d1.user.data"))) +// Uninitialized data in cached D1 RAM +#define D1_C_BSS __attribute__((section(".ram_d1.user.bss"))) +// Read-only data in cached D1 RAM (mainly for rx buffers) @note Not protected by MPU +#define D1_C_RODATA __attribute__((section(".ram_d1.user.rodata"))) const +#define D1_C_DATA_INLINE(name) \ + inline __attribute__((section(MPU_SECTION_WITH_NAME(".ram_d1.user.data", name)))) +#define D1_C_BSS_INLINE(name) \ + inline __attribute__((section(MPU_SECTION_WITH_NAME(".ram_d1.user.bss", name)))) +#define D1_C_RODATA_INLINE(name) \ + inline __attribute__((section(MPU_SECTION_WITH_NAME(".ram_d1.user.rodata", name)))) const +// Initialized data in cached D2 RAM +#define D2_C_DATA __attribute__((section(".ram_d2.user.data"))) +// Uninitialized data in cached D2 RAM +#define D2_C_BSS __attribute__((section(".ram_d2.user.bss"))) +// Read-only data in cached D2 RAM (mainly for rx buffers) @note Not protected by MPU +#define D2_C_RODATA __attribute__((section(".ram_d2.user.rodata"))) const +#define D2_C_DATA_INLINE(name) \ + inline __attribute__((section(MPU_SECTION_WITH_NAME(".ram_d2.user.data", name)))) +#define D2_C_BSS_INLINE(name) \ + inline __attribute__((section(MPU_SECTION_WITH_NAME(".ram_d2.user.bss", name)))) +#define D2_C_RODATA_INLINE(name) \ + inline __attribute__((section(MPU_SECTION_WITH_NAME(".ram_d2.user.rodata", name)))) const +// Initialized data in cached D3 RAM +#define D3_C_DATA __attribute__((section(".ram_d3.user.data"))) +// Uninitialized data in cached D3 RAM +#define D3_C_BSS __attribute__((section(".ram_d3.user.bss"))) +// Read-only data in cached D3 RAM (mainly for rx buffers) @note Not protected by MPU +#define D3_C_RODATA __attribute__((section(".ram_d3.user.rodata"))) const +#define D3_C_DATA_INLINE(name) \ + inline __attribute__((section(MPU_SECTION_WITH_NAME(".ram_d3.user.data", name)))) +#define D3_C_BSS_INLINE(name) \ + inline __attribute__((section(MPU_SECTION_WITH_NAME(".ram_d3.user.bss", name)))) +#define D3_C_RODATA_INLINE(name) \ + inline __attribute__((section(MPU_SECTION_WITH_NAME(".ram_d3.user.rodata", name)))) const + #define RAM_CODE __attribute__((section(".ram_code"))) +#define RAM_CODE_INLINE(name) \ + inline __attribute__((section(MPU_SECTION_WITH_NAME(".ram_code", name)))) + +// Constants in DTCM (default is FLASH because DTCM is small) @note Not protected by MPU +#define DTCM_RODATA __attribute__((section(".dtcm.rodata"))) const +#define DTCM_RODATA_INLINE(name) \ + inline __attribute__((section(MPU_SECTION_WITH_NAME(".dtcm.rodata", name)))) const + #endif +// Retrocompatibility macros +#define D1_NC D1_NC_BSS +#define D2_NC D2_NC_BSS +#define D3_NC D3_NC_BSS +#define D1_C D1_C_BSS +#define D2_C D2_C_BSS +#define D3_C D3_C_BSS + // Memory Bank Symbols from Linker -extern "C" const char __itcm_base; -extern "C" const char __itcm_size; -extern "C" const char __dtcm_base; -extern "C" const char __dtcm_size; -extern "C" const char __flash_base; -extern "C" const char __flash_size; -extern "C" const char __ram_d1_base; -extern "C" const char __ram_d1_size; -extern "C" const char __ram_d2_base; -extern "C" const char __ram_d2_size; -extern "C" const char __ram_d3_base; -extern "C" const char __ram_d3_size; -extern "C" const char __peripheral_base; -extern "C" const char __peripheral_size; +extern "C" const char _itcm_base; +extern "C" const char _itcm_size; +extern "C" const char _dtcm_base; +extern "C" const char _dtcm_size; +extern "C" const char _flash_base; +extern "C" const char _flash_size; +extern "C" const char _ram_d1_base; +extern "C" const char _ram_d1_size; +extern "C" const char _ram_d2_base; +extern "C" const char _ram_d2_size; +extern "C" const char _ram_d3_base; +extern "C" const char _ram_d3_size; +extern "C" const char _peripheral_base; +extern "C" const char _peripheral_size; // MPU Non-Cached Section Symbols from Linker -extern "C" const char __mpu_d1_nc_start; -extern "C" const char __mpu_d1_nc_end; -extern "C" const char __mpu_d2_nc_start; -extern "C" const char __mpu_d2_nc_end; -extern "C" const char __mpu_d3_nc_start; -extern "C" const char __mpu_d3_nc_end; +extern "C" const char _ram_d1_nc_start; +extern "C" const char _ram_d1_nc_end; +extern "C" const char _ram_d2_nc_start; +extern "C" const char _ram_d2_nc_end; +extern "C" const char _ram_d3_nc_start; +extern "C" const char _ram_d3_nc_end; inline constexpr std::array mpu_supported_alignments = {32, 16, 8, 4, 2, 1}; @@ -281,9 +403,9 @@ struct MPUDomain { template auto& construct(Args&&... args) { using Request = std::remove_cvref_t; static_assert(mpu_buffer_request, "Target must be a valid MPUDomain buffer"); - constexpr bool is_nc = Request::e.memory_type == MemoryType::NonCached; + constexpr bool is_nc = Target.e.memory_type == MemoryType::NonCached; static_assert( - is_nc && std::is_volatile_v, + !is_nc || std::is_volatile_v, "Non cached buffers must be volatile to work as intended" ); using T = typename Request::buffer_type; @@ -293,9 +415,9 @@ struct MPUDomain { template auto* as() { using Request = std::remove_cvref_t; static_assert(mpu_buffer_request, "Target must be a valid MPUDomain buffer"); - constexpr bool is_nc = Request::e.memory_type == MemoryType::NonCached; + constexpr bool is_nc = Target.e.memory_type == MemoryType::NonCached; static_assert( - is_nc && std::is_volatile_v, + !is_nc || std::is_volatile_v, "Non cached buffers must be volatile to work as intended" ); using T = typename Request::buffer_type; @@ -323,32 +445,35 @@ struct MPUDomain { static constexpr auto Sizes = calculate_total_sizes(cfgs); - // Sections defined in Linker Script (aligned to 32 bytes just in case) #ifdef SIM_ON - alignas(32 - ) static inline uint8_t d1_nc_buffer[Sizes.d1_nc_total > 0 ? Sizes.d1_nc_total : 1]; + + alignas(32) static inline volatile uint8_t + d1_nc_buffer[Sizes.d1_nc_total > 0 ? Sizes.d1_nc_total : 1]; alignas(32) static inline uint8_t d1_c_buffer[Sizes.d1_c_total > 0 ? Sizes.d1_c_total : 1]; - alignas(32 - ) static inline uint8_t d2_nc_buffer[Sizes.d2_nc_total > 0 ? Sizes.d2_nc_total : 1]; + alignas(32) static inline volatile uint8_t + d2_nc_buffer[Sizes.d2_nc_total > 0 ? Sizes.d2_nc_total : 1]; alignas(32) static inline uint8_t d2_c_buffer[Sizes.d2_c_total > 0 ? Sizes.d2_c_total : 1]; - alignas(32 - ) static inline uint8_t d3_nc_buffer[Sizes.d3_nc_total > 0 ? Sizes.d3_nc_total : 1]; + alignas(32) static inline volatile uint8_t + d3_nc_buffer[Sizes.d3_nc_total > 0 ? Sizes.d3_nc_total : 1]; alignas(32) static inline uint8_t d3_c_buffer[Sizes.d3_c_total > 0 ? Sizes.d3_c_total : 1]; + #else - __attribute__((section(".mpu_ram_d1_nc.buffer"))) alignas(32 - ) static inline uint8_t d1_nc_buffer[Sizes.d1_nc_total > 0 ? Sizes.d1_nc_total : 1]; + + __attribute__((section(".ram_d1_nc.buffer"))) alignas(32) static inline volatile uint8_t + d1_nc_buffer[Sizes.d1_nc_total > 0 ? Sizes.d1_nc_total : 1]; __attribute__((section(".ram_d1.buffer"))) alignas(32 ) static inline uint8_t d1_c_buffer[Sizes.d1_c_total > 0 ? Sizes.d1_c_total : 1]; - __attribute__((section(".mpu_ram_d2_nc.buffer"))) alignas(32) static inline volatile uint8_t + __attribute__((section(".ram_d2_nc.buffer"))) alignas(32) static inline volatile uint8_t d2_nc_buffer[Sizes.d2_nc_total > 0 ? Sizes.d2_nc_total : 1]; __attribute__((section(".ram_d2.buffer"))) alignas(32 ) static inline uint8_t d2_c_buffer[Sizes.d2_c_total > 0 ? Sizes.d2_c_total : 1]; - __attribute__((section(".mpu_ram_d3_nc.buffer"))) alignas(32) static inline volatile uint8_t + __attribute__((section(".ram_d3_nc.buffer"))) alignas(32) static inline volatile uint8_t d3_nc_buffer[Sizes.d3_nc_total > 0 ? Sizes.d3_nc_total : 1]; __attribute__((section(".ram_d3.buffer"))) alignas(32 ) static inline uint8_t d3_c_buffer[Sizes.d3_c_total > 0 ? Sizes.d3_c_total : 1]; + #endif static void init() { @@ -357,18 +482,18 @@ struct MPUDomain { // Dynamic Configuration based on Linker Symbols configure_dynamic_region( - reinterpret_cast(&__mpu_d1_nc_start), - reinterpret_cast(&__mpu_d1_nc_end), + reinterpret_cast(&_ram_d1_nc_start), + reinterpret_cast(&_ram_d1_nc_end), MPU_REGION_NUMBER3 ); configure_dynamic_region( - reinterpret_cast(&__mpu_d2_nc_start), - reinterpret_cast(&__mpu_d2_nc_end), + reinterpret_cast(&_ram_d2_nc_start), + reinterpret_cast(&_ram_d2_nc_end), MPU_REGION_NUMBER5 ); configure_dynamic_region( - reinterpret_cast(&__mpu_d3_nc_start), - reinterpret_cast(&__mpu_d3_nc_end), + reinterpret_cast(&_ram_d3_nc_start), + reinterpret_cast(&_ram_d3_nc_end), MPU_REGION_NUMBER7 ); @@ -440,8 +565,8 @@ struct MPUDomain { // Peripherals (Device, Buffered) // Guarded against speculative execution and cache configure_region( - reinterpret_cast(&__peripheral_base), - reinterpret_cast(&__peripheral_size), + reinterpret_cast(&_peripheral_base), + reinterpret_cast(&_peripheral_size), MPU_REGION_NUMBER8, MPU_TEX_LEVEL0, MPU_REGION_FULL_ACCESS, @@ -455,8 +580,8 @@ struct MPUDomain { // TEX=0, C=1, B=0: Normal, Write-Through, No Read-Allocate (Read optimized) // Not Shareable to allow full caching configure_region( - reinterpret_cast(&__flash_base), - reinterpret_cast(&__flash_size), + reinterpret_cast(&_flash_base), + reinterpret_cast(&_flash_size), MPU_REGION_NUMBER1, MPU_TEX_LEVEL0, MPU_REGION_FULL_ACCESS, @@ -470,8 +595,8 @@ struct MPUDomain { // TEX=1, C=1, B=1: Normal, Write-Back, Write and Read Allocate // TCMs are like Cache, so they are not really cacheable, and the MPU settings are ignored configure_region( - reinterpret_cast(&__dtcm_base), - reinterpret_cast(&__dtcm_size), + reinterpret_cast(&_dtcm_base), + reinterpret_cast(&_dtcm_size), MPU_REGION_NUMBER10, MPU_TEX_LEVEL1, MPU_REGION_FULL_ACCESS, @@ -485,8 +610,8 @@ struct MPUDomain { // TEX=0, C=1, B=0: Normal, Write-Through, No Read-Allocate (Read optimized) // TCMs are like Cache, so they are not really cacheable, and the MPU settings are ignored configure_region( - reinterpret_cast(&__itcm_base), - reinterpret_cast(&__itcm_size), + reinterpret_cast(&_itcm_base), + reinterpret_cast(&_itcm_size), MPU_REGION_NUMBER11, MPU_TEX_LEVEL0, MPU_REGION_FULL_ACCESS, @@ -496,12 +621,25 @@ struct MPUDomain { MPU_ACCESS_NOT_BUFFERABLE ); + // Null-pointer guard: blocks first 32 bytes of ITCM to catch null dereferences + configure_region( + 0x00000000, + 32, + MPU_REGION_NUMBER12, + MPU_TEX_LEVEL0, + MPU_REGION_NO_ACCESS, + MPU_INSTRUCTION_ACCESS_DISABLE, + MPU_ACCESS_NOT_SHAREABLE, + MPU_ACCESS_NOT_CACHEABLE, + MPU_ACCESS_NOT_BUFFERABLE + ); + // D1 RAM Cached (Normal, WBWA) // TEX=1, C=1, B=1: Normal, Write-Back, Write-Allocate // Shareable since it can be accessed by multiple masters (CPU, DMA, etc) configure_region( - reinterpret_cast(&__ram_d1_base), - reinterpret_cast(&__ram_d1_size), + reinterpret_cast(&_ram_d1_base), + reinterpret_cast(&_ram_d1_size), MPU_REGION_NUMBER2, MPU_TEX_LEVEL1, MPU_REGION_FULL_ACCESS, @@ -515,8 +653,8 @@ struct MPUDomain { // TEX=1, C=1, B=1: Normal, Write-Back, Write-Allocate // Shareable since it can be accessed by multiple masters (CPU, DMA, etc) configure_region( - reinterpret_cast(&__ram_d2_base), - reinterpret_cast(&__ram_d2_size), + reinterpret_cast(&_ram_d2_base), + reinterpret_cast(&_ram_d2_size), MPU_REGION_NUMBER4, MPU_TEX_LEVEL1, MPU_REGION_FULL_ACCESS, @@ -530,8 +668,8 @@ struct MPUDomain { // TEX=1, C=1, B=1: Normal, Write-Back, Write-Allocate // Shareable since it can be accessed by multiple masters (CPU, DMA, etc) configure_region( - reinterpret_cast(&__ram_d3_base), - reinterpret_cast(&__ram_d3_size), + reinterpret_cast(&_ram_d3_base), + reinterpret_cast(&_ram_d3_size), MPU_REGION_NUMBER6, MPU_TEX_LEVEL1, MPU_REGION_FULL_ACCESS, diff --git a/Inc/HALAL/Services/ADC/ADC.hpp b/Inc/HALAL/Services/ADC/ADC.hpp index 8f6dbc920..4a204eebd 100644 --- a/Inc/HALAL/Services/ADC/ADC.hpp +++ b/Inc/HALAL/Services/ADC/ADC.hpp @@ -13,10 +13,10 @@ #include "HALAL/Models/Pin.hpp" #ifdef SIM_ON -#define STLIB_ADC_DMA_BUFFER_ATTR +#define STLIB_ADC_DMA_BUFFER_ATTR(x) inline #else #include "HALAL/Models/MPU.hpp" -#define STLIB_ADC_DMA_BUFFER_ATTR D1_NC +#define STLIB_ADC_DMA_BUFFER_ATTR(x) D2_NC_BSS_INLINE(x) #endif using std::array; @@ -780,8 +780,8 @@ struct ADCDomain { "ADC DMA buffer size exceeds max_instances" ); - alignas(32) STLIB_ADC_DMA_BUFFER_ATTR - static inline uint16_t dma_buffer_pool[total_dma_slots > 0 ? total_dma_slots : 1]{}; + alignas(32) static uint16_t STLIB_ADC_DMA_BUFFER_ATTR(dma_buffer_pool + ) dma_buffer_pool[total_dma_slots > 0 ? total_dma_slots : 1]{}; static constexpr bool is_resolved_config(const Config& cfg) { return cfg.peripheral != Peripheral::AUTO && cfg.channel != Channel::AUTO; diff --git a/Inc/HALAL/Services/DFSDM/DFSDM.hpp b/Inc/HALAL/Services/DFSDM/DFSDM.hpp index a68e8c9ff..9d13130f1 100644 --- a/Inc/HALAL/Services/DFSDM/DFSDM.hpp +++ b/Inc/HALAL/Services/DFSDM/DFSDM.hpp @@ -6,7 +6,7 @@ #include "HALAL/Models/DMA/DMA2.hpp" #include "HALAL/Models/MPU.hpp" -#define STLIB_DFSDM_DMA_BUFFER_ATTR D1_NC +#define STLIB_DFSDM_DMA_BUFFER_ATTR(x) D2_NC_BSS_INLINE(x) #define Oversampling_MAX 1024 #define Oversampling_MAX_Filter_4 215 @@ -992,14 +992,14 @@ struct DFSDM_CHANNEL_DOMAIN { sizes.filter0 + sizes.filter1 + sizes.filter2 + sizes.filter3; // Filter Buffers - alignas(32) STLIB_DFSDM_DMA_BUFFER_ATTR - static inline int32_t Buffer_Filter0[sizes.filter0 > 0 ? sizes.filter0 : 1]{}; - alignas(32) STLIB_DFSDM_DMA_BUFFER_ATTR - static inline int32_t Buffer_Filter1[sizes.filter1 > 0 ? sizes.filter1 : 1]{}; - alignas(32) STLIB_DFSDM_DMA_BUFFER_ATTR - static inline int32_t Buffer_Filter2[sizes.filter2 > 0 ? sizes.filter2 : 1]{}; - alignas(32) STLIB_DFSDM_DMA_BUFFER_ATTR - static inline int32_t Buffer_Filter3[sizes.filter3 > 0 ? sizes.filter3 : 1]{}; + alignas(32) STLIB_DFSDM_DMA_BUFFER_ATTR(Buffer_Filter0 + ) static int32_t Buffer_Filter0[sizes.filter0 > 0 ? sizes.filter0 : 1]{}; + alignas(32) STLIB_DFSDM_DMA_BUFFER_ATTR(Buffer_Filter1 + ) static int32_t Buffer_Filter1[sizes.filter1 > 0 ? sizes.filter1 : 1]{}; + alignas(32) STLIB_DFSDM_DMA_BUFFER_ATTR(Buffer_Filter2 + ) static int32_t Buffer_Filter2[sizes.filter2 > 0 ? sizes.filter2 : 1]{}; + alignas(32) STLIB_DFSDM_DMA_BUFFER_ATTR(Buffer_Filter3 + ) static int32_t Buffer_Filter3[sizes.filter3 > 0 ? sizes.filter3 : 1]{}; static inline std::array instances{}; diff --git a/Inc/MockedDrivers/stm32h7xx_hal_mock.h b/Inc/MockedDrivers/stm32h7xx_hal_mock.h index 283e2c55b..1dd15a841 100644 --- a/Inc/MockedDrivers/stm32h7xx_hal_mock.h +++ b/Inc/MockedDrivers/stm32h7xx_hal_mock.h @@ -1238,6 +1238,7 @@ enum { #define MPU_REGION_NUMBER8 (0x08U) #define MPU_REGION_NUMBER10 (0x0AU) #define MPU_REGION_NUMBER11 (0x0BU) +#define MPU_REGION_NUMBER12 (0x0CU) #define MPU_REGION_ENABLE (0x01U) #define MPU_REGION_SIZE_4GB (0x1FU) diff --git a/Inc/ST-LIB.hpp b/Inc/ST-LIB.hpp index 7315e1cae..b48921c3e 100644 --- a/Inc/ST-LIB.hpp +++ b/Inc/ST-LIB.hpp @@ -385,3 +385,10 @@ template struct Board { }; } // namespace ST_LIB + +/** + * @brief This is a function that gets called early in the startup process, + * before the global constructors and main() are called. + * It is responsible for initializing the hardware and peripherals + */ +extern "C" void BoardInit(void); diff --git a/LinkerScript.ld b/LinkerScript.ld new file mode 100644 index 000000000..dfc6f7e24 --- /dev/null +++ b/LinkerScript.ld @@ -0,0 +1,540 @@ +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +__sstack = ORIGIN(DTCMRAM); +__estack = ORIGIN(DTCMRAM) + LENGTH(DTCMRAM); +PROVIDE(_sstack = __sstack); +PROVIDE(_estack = __estack); +/* Generate a link error if heap and stack don't fit into DTCM */ +__Min_Heap_Size = 0x200; /* required amount of heap */ +__Min_Stack_Size = 0x400; /* required amount of stack */ +PROVIDE(_Min_Heap_Size = __Min_Heap_Size); +PROVIDE(_Min_Stack_Size = __Min_Stack_Size); + +#if !defined(__ITCM_SIZE) + #define __ITCM_SIZE (64K) /* Default ITCM size if not defined by the build system */ +#endif +ASSERT((__ITCM_SIZE == 64K) || (__ITCM_SIZE == 128K) || (__ITCM_SIZE == 192K) || (__ITCM_SIZE == 256K), \ + "Invalid ITCM size. Must be 64K, 128K, 192K, or 256K") + +#if !defined(__ITCM_BUILD) + #define __ITCM_BUILD 0 /* By default, code is goes to just FLASH. It can be enabled via build system if needed. */ +#endif + +/* Specify the memory areas */ +MEMORY +{ + ITCMRAM (xrw) : ORIGIN = 0x00000000, LENGTH = __ITCM_SIZE /* Configurable ITCM size, default to 64K */ + DTCMRAM (rw) : ORIGIN = 0x20000000, LENGTH = 128K + FLASH (xr) : ORIGIN = 0x08000000, LENGTH = 1024K - 128K - 128K + FLASH_ST (xr) : ORIGIN = 0x080C0000, LENGTH = 128K + FLASH_BT (xr) : ORIGIN = 0x080E0000, LENGTH = 128K + RAM_D1 (rw) : ORIGIN = 0x24000000, LENGTH = 320K - (__ITCM_SIZE - 64K) /* ITCM memory is carved out of D1 RAM */ + RAM_D2 (rw) : ORIGIN = 0x30000000, LENGTH = 32K + RAM_D3 (rw) : ORIGIN = 0x38000000, LENGTH = 16K + PERIPHERAL (rw) : ORIGIN = 0x40000000, LENGTH = 512M +} + +/* Define output sections */ +SECTIONS +{ + /* Export Memory Layout Information for MPU Configuration (dynamic symbols are defined later) */ + PROVIDE(_itcm_base = ABSOLUTE(ORIGIN(ITCMRAM))); + PROVIDE(_itcm_size = ABSOLUTE(LENGTH(ITCMRAM))); + PROVIDE(_dtcm_base = ABSOLUTE(ORIGIN(DTCMRAM))); + PROVIDE(_dtcm_size = ABSOLUTE(LENGTH(DTCMRAM))); + PROVIDE(_flash_base = ABSOLUTE(ORIGIN(FLASH))); + PROVIDE(_flash_size = ABSOLUTE(LENGTH(FLASH) + LENGTH(FLASH_ST) + LENGTH(FLASH_BT))); + PROVIDE(_ram_d1_base = ABSOLUTE(ORIGIN(RAM_D1))); + PROVIDE(_ram_d1_size = ABSOLUTE(LENGTH(RAM_D1))); + PROVIDE(_ram_d2_base = ABSOLUTE(ORIGIN(RAM_D2))); + PROVIDE(_ram_d2_size = ABSOLUTE(LENGTH(RAM_D2))); + PROVIDE(_ram_d3_base = ABSOLUTE(ORIGIN(RAM_D3))); + PROVIDE(_ram_d3_size = ABSOLUTE(LENGTH(RAM_D3))); + PROVIDE(_peripheral_base = ABSOLUTE(ORIGIN(PERIPHERAL))); + PROVIDE(_peripheral_size = ABSOLUTE(LENGTH(PERIPHERAL))); + + /* Null-pointer guard: MPU blocks first 32 bytes. VTOR requires 128-byte alignment. */ + .null_guard (NOLOAD) : + { + . += 32; + . = ALIGN(1024); // 156 vectors * 4 bytes each = 624 bytes, next power of 2 is 1024 + } >ITCMRAM + + /* The interrupt vector table goes into ITCM RAM */ + .isr_vector : + { + . = ALIGN(4); + __sisr_vector = ABSOLUTE(.); + KEEP(*(.isr_vector)) /* Interrupt vector table */ + + . = ALIGN(4); + __eisr_vector = ABSOLUTE(.); + } >ITCMRAM AT>FLASH + __si_isr_vector = LOADADDR(.isr_vector); + + /* This section ALWAYS stays in Flash */ + .boot : + { + . = ALIGN(4); + *(.boot_code*) /* Everything tagged with .boot_code stays here */ + . = ALIGN(4); + } >FLASH + + /* The program code goes into FLASH */ + .text : + { + . = ALIGN(4); + __stext = ABSOLUTE(.); + PROVIDE(_stext = __stext); + +#if !__ITCM_BUILD + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) /* Exception handling frames, mainly for the debugger */ +#endif + + KEEP(*(.init)) + KEEP(*(.fini)) + + . = ALIGN(4); + __etext = ABSOLUTE(.); + PROVIDE(_etext = __etext); + } >FLASH + + /* Code running in ITCM RAM (0 Wait States, Instruction Bus) */ + .ram_code : + { + . = ALIGN(4); + __sram_code = ABSOLUTE(.); + *(.ram_code) /* .ram_code sections, for code marked to be placed in ITCM RAM */ + *(.ram_code*) /* .ram_code* sections, for code marked to be placed in ITCM RAM */ + +#if __ITCM_BUILD + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) /* Exception handling frames, mainly for the debugger */ +#endif + + . = ALIGN(4); + __eram_code = ABSOLUTE(.); + } >ITCMRAM AT> FLASH + __si_ram_code = LOADADDR(.ram_code); + + /* Constant data goes into FLASH */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + + . = ALIGN(4); + } >FLASH + + /* ARM exception handling tables go into FLASH */ + .ARM.extab (READONLY): { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM (READONLY): { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array (READONLY): + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + + .init_array (READONLY): + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + + .fini_array (READONLY): + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* .hard_fault_log has to be the first thing in the FLASH_ST */ + .hardfault_log : + { + . = ALIGN(4); + __hf_log = .; + KEEP(*(.hardfault_log)); + . += 0x200; + + . = ALIGN(4); + PROVIDE(_hf_log = __hf_log); + } >FLASH_ST + + .metadata_pool : + { + . = ALIGN(4); + __metadata = .; + KEEP(*(.metadata_pool)) + . += 0x100; + + . = ALIGN(4); + PROVIDE(_metadata = __metadata); + } >FLASH_ST + + /* Stack memory to avoid memfault inside hardfault handler, at the start of DTCM */ + .hardfault_stack (NOLOAD) : + { + . = ALIGN(8); + __hf_stack_start = .; + PROVIDE(_hf_stack_start = __hf_stack_start); + . += 0x400; /* 1 KB */ + + . = ALIGN(8); + __hf_stack_end = .; + PROVIDE(_hf_stack_end = __hf_stack_end); + } >DTCMRAM + + /* Initialized data sections goes into RAM, copied from FLASH */ + .data : + { + . = ALIGN(4); + __sdata = .; + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + __edata = .; + } >DTCMRAM AT> FLASH + __si_data = LOADADDR(.data); + + .dtcm_rodata : + { + . = ALIGN(4); + __sdtcm_rodata = .; + *(.dtcm.rodata) /* .dtcm_rodata sections, for constants marked to be placed in DTCM RAM */ + *(.dtcm.rodata*) /* .dtcm_rodata* sections, for constants marked to be placed in DTCM RAM */ + BYTE(0); + + . = ALIGN(4); + __edtcm_rodata = .; + } >DTCMRAM AT> FLASH + __si_dtcm_rodata = LOADADDR(.dtcm_rodata); + + /* Uninitialized data section */ + .bss (NOLOAD) : + { + . = ALIGN(4); + __sbss = .; + __bss_start__ = __sbss; + *(.bss) /* .bss sections */ + *(.bss*) /* .bss* sections */ + *(COMMON) /* common sections, same as the bss, mainly generated by legacy code */ + + . = ALIGN(4); + __ebss = .; + __bss_end__ = __ebss; + } >DTCMRAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack (NOLOAD) : + { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + __Min_Heap_Size; + . = . + __Min_Stack_Size; + + . = ALIGN(8); + } >DTCMRAM + + /* MPU D1 Non-Cached Section: Placed at start of RAM_D1 for alignment */ + .ram_d1_nc_bss (NOLOAD) : + { + . = ALIGN(32); + __d1_nc_start = ABSOLUTE(.); + __sram_d1_nc_bss = ABSOLUTE(.); + + /* MPU system buffers */ + *(.ram_d1_nc.buffer) + *(.ram_d1_nc.buffer*) + + /* User manual allocations via D1_NC macro */ + . = ALIGN(32); + *(.ram_d1_nc.user.bss) + *(.ram_d1_nc.user.bss*) + + /* Ethernet Rx Pool */ + . = ALIGN(32); + *(.Rx_PoolSection) + + __eram_d1_nc_bss = ABSOLUTE(.); + } >RAM_D1 + .ram_d1_nc_data_rodata : + { + . = ALIGN(32); + __sram_d1_nc_data = ABSOLUTE(.); + + *(.ram_d1_nc.user.data) + *(.ram_d1_nc.user.data*) + *(.ram_d1_nc.user.rodata) + *(.ram_d1_nc.user.rodata*) + BYTE(0); + + __eram_d1_nc_data = ABSOLUTE(.); + } >RAM_D1 AT> FLASH + __si_d1_nc_data = LOADADDR(.ram_d1_nc_data_rodata); + /* Calculate padding for MPU subregions (D1) */ + __d1_size = . - __d1_nc_start; + /* Find next power of 2 (up to 512KB for 320KB RAM) */ + __d1_p2 = (1 << LOG2CEIL(MAX(32, __d1_size))); + /* Subregion size is RegionSize / 8 */ + __d1_sub = __d1_p2 / 8; + /* Align effective size to the subregion granularity */ + __d1_pad = (__d1_size + __d1_sub - 1) / __d1_sub * __d1_sub; + /* Advance current pointer to reserve this space */ + . = __d1_nc_start + __d1_pad; + __d1_nc_end = ABSOLUTE(.); + PROVIDE(_ram_d1_nc_start = __d1_nc_start); + PROVIDE(_ram_d1_nc_end = __d1_nc_end); + + /* MPU D1 Cached Section */ + .ram_d1_bss (NOLOAD) : + { + . = ALIGN(32); + __d1_start = ABSOLUTE(.); + __sram_d1_bss = ABSOLUTE(.); + + /* User manual allocations via D1_C macro */ + *(.ram_d1.user.bss) + *(.ram_d1.user.bss*) + + /* MPU system buffers */ + *(.ram_d1.buffer) + __eram_d1_bss = ABSOLUTE(.); + } >RAM_D1 + .ram_d1_data_rodata : + { + . = ALIGN(32); + __sram_d1_data = ABSOLUTE(.); + + *(.ram_d1.user.data) + *(.ram_d1.user.data*) + *(.ram_d1.user.rodata) + *(.ram_d1.user.rodata*) + BYTE(0); + + __eram_d1_data = ABSOLUTE(.); + __d1_end = ABSOLUTE(.); + } >RAM_D1 AT> FLASH + __si_d1_data = LOADADDR(.ram_d1_data_rodata); + + /* MPU D2 Non-Cached Section: Contains Ethernet Descriptors and Generic Buffers */ + .ram_d2_nc_bss (NOLOAD) : + { + . = ALIGN(32); + __d2_nc_start = ABSOLUTE(.); + __sram_d2_nc_bss = ABSOLUTE(.); + + /* ETH Descriptors - Must be aligned */ + *(.RxDecripSection) + *(.TxDecripSection) + + /* MPU system buffers */ + *(.ram_d2_nc.buffer) + *(.ram_d2_nc.buffer*) + + /* User manual allocations via D2_NC macro */ + *(.ram_d2_nc.user.bss) + *(.ram_d2_nc.user.bss*) + __eram_d2_nc_bss = ABSOLUTE(.); + } >RAM_D2 + .ram_d2_nc_data_rodata : + { + . = ALIGN(32); + __sram_d2_nc_data = ABSOLUTE(.); + + *(.ram_d2_nc.user.data) + *(.ram_d2_nc.user.data*) + *(.ram_d2_nc.user.rodata) + *(.ram_d2_nc.user.rodata*) + BYTE(0); + + __eram_d2_nc_data = ABSOLUTE(.); + } >RAM_D2 AT> FLASH + __si_d2_nc_data = LOADADDR(.ram_d2_nc_data_rodata); + /* Calculate padding for MPU subregions (D2) */ + __d2_size = . - __d2_nc_start; + /* Find next power of 2 (up to 64KB for 32KB RAM) */ + __d2_p2 = (1 << LOG2CEIL(MAX(32, __d2_size))); + __d2_sub = __d2_p2 / 8; + __d2_pad = (__d2_size + __d2_sub - 1) / __d2_sub * __d2_sub; + . = __d2_nc_start + __d2_pad; + __d2_nc_end = ABSOLUTE(.); + PROVIDE(_ram_d2_nc_start = __d2_nc_start); + PROVIDE(_ram_d2_nc_end = __d2_nc_end); + + /* MPU D2 Cached Section */ + .ram_d2_bss (NOLOAD) : + { + . = ALIGN(32); + __d2_start = ABSOLUTE(.); + __sram_d2_bss = ABSOLUTE(.); + + /* User manual allocations via D2_C macro */ + *(.ram_d2.user.bss) + *(.ram_d2.user.bss*) + + /* MPU system buffers */ + *(.ram_d2.buffer) + *(.ram_d2.buffer*) + __eram_d2_bss = ABSOLUTE(.); + } >RAM_D2 + .ram_d2_data_rodata : + { + . = ALIGN(32); + __sram_d2_data = ABSOLUTE(.); + + *(.ram_d2.user.data) + *(.ram_d2.user.data*) + *(.ram_d2.user.rodata) + *(.ram_d2.user.rodata*) + BYTE(0); + + __eram_d2_data = ABSOLUTE(.); + __d2_end = ABSOLUTE(.); + } >RAM_D2 AT> FLASH + __si_d2_data = LOADADDR(.ram_d2_data_rodata); + + /* MPU D3 Non-Cached Section */ + .ram_d3_nc_bss (NOLOAD) : + { + . = ALIGN(32); + __d3_nc_start = ABSOLUTE(.); + __sram_d3_nc_bss = ABSOLUTE(.); + + /* New MPU system buffers */ + *(.ram_d3_nc.buffer) + + /* Legacy MPUManager allocations */ + *(.ram_d3_nc.legacy) + + /* User manual allocations via D3_NC macro */ + *(.ram_d3_nc.user.bss) + *(.ram_d3_nc.user.bss*) + __eram_d3_nc_bss = ABSOLUTE(.); + } >RAM_D3 + .ram_d3_nc_data_rodata : + { + . = ALIGN(32); + __sram_d3_nc_data = ABSOLUTE(.); + + *(.ram_d3_nc.user.data) + *(.ram_d3_nc.user.data*) + *(.ram_d3_nc.user.rodata) + *(.ram_d3_nc.user.rodata*) + BYTE(0); + + __eram_d3_nc_data = ABSOLUTE(.); + } >RAM_D3 AT> FLASH + __si_d3_nc_data = LOADADDR(.ram_d3_nc_data_rodata); + /* Calculate padding for MPU subregions (D3) */ + __d3_size = . - __d3_nc_start; + /* Find next power of 2 (up to 32KB for 16KB RAM) */ + __d3_p2 = (1 << LOG2CEIL(MAX(32, __d3_size))); + __d3_sub = __d3_p2 / 8; + __d3_pad = (__d3_size + __d3_sub - 1) / __d3_sub * __d3_sub; + . = __d3_nc_start + __d3_pad; + __d3_nc_end = ABSOLUTE(.); + PROVIDE(_ram_d3_nc_start = __d3_nc_start); + PROVIDE(_ram_d3_nc_end = __d3_nc_end); + + /* MPU D3 Cached Section */ + .ram_d3_bss (NOLOAD) : + { + . = ALIGN(32); + __d3_start = ABSOLUTE(.); + __sram_d3_bss = ABSOLUTE(.); + + /* User manual allocations via D3_C macro */ + *(.ram_d3.user.bss) + *(.ram_d3.user.bss*) + + /* New MPU system buffers */ + *(.ram_d3.buffer) + *(.ram_d3.user.bss) + __eram_d3_bss = ABSOLUTE(.); + } >RAM_D3 + .ram_d3_data_rodata : + { + . = ALIGN(32); + __sram_d3_data = ABSOLUTE(.); + + *(.ram_d3.user.data) + *(.ram_d3.user.data*) + *(.ram_d3.user.rodata) + *(.ram_d3.user.rodata*) + BYTE(0); + + __eram_d3_data = ABSOLUTE(.); + __d3_end = ABSOLUTE(.); + } >RAM_D3 AT> FLASH + __si_d3_data = LOADADDR(.ram_d3_data_rodata); + + /* Table of sections to be copied from Flash to RAM */ + .copy_table : + { + . = ALIGN(4); + __copy_table_start = .; + + /* [Source LMA, Dest VMA Start, Dest VMA End] */ + LONG(__si_isr_vector); LONG(__sisr_vector); LONG(__eisr_vector); + LONG(__si_ram_code); LONG(__sram_code); LONG(__eram_code); + LONG(__si_data); LONG(__sdata); LONG(__edata); + LONG(__si_dtcm_rodata); LONG(__sdtcm_rodata); LONG(__edtcm_rodata); + LONG(__si_d1_nc_data); LONG(__sram_d1_nc_data); LONG(__eram_d1_nc_data); + LONG(__si_d1_data); LONG(__sram_d1_data); LONG(__eram_d1_data); + LONG(__si_d2_nc_data); LONG(__sram_d2_nc_data); LONG(__eram_d2_nc_data); + LONG(__si_d2_data); LONG(__sram_d2_data); LONG(__eram_d2_data); + LONG(__si_d3_nc_data); LONG(__sram_d3_nc_data); LONG(__eram_d3_nc_data); + LONG(__si_d3_data); LONG(__sram_d3_data); LONG(__eram_d3_data); + + __copy_table_end = .; + } > FLASH + + /* Table of sections to be zero-initialized in RAM */ + .zero_table : + { + . = ALIGN(4); + __zero_table_start = .; + + /* [Dest VMA Start, Dest VMA End] */ + LONG(__sbss); LONG(__ebss); + LONG(__sram_d1_nc_bss); LONG(__eram_d1_nc_bss); + LONG(__sram_d1_bss); LONG(__eram_d1_bss); + LONG(__sram_d2_nc_bss); LONG(__eram_d2_nc_bss); + LONG(__sram_d2_bss); LONG(__eram_d2_bss); + LONG(__sram_d3_nc_bss); LONG(__eram_d3_nc_bss); + LONG(__sram_d3_bss); LONG(__eram_d3_bss); + + __zero_table_end = .; + } > FLASH + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } /* Metadata, not allocated, only exists in the .elf */ +} diff --git a/STM32H723ZGTX_FLASH.ld b/STM32H723ZGTX_FLASH.ld deleted file mode 100644 index 5e9e3f041..000000000 --- a/STM32H723ZGTX_FLASH.ld +++ /dev/null @@ -1,354 +0,0 @@ -/* -****************************************************************************** -** -** File : LinkerScript.ld -** -** Author : STM32CubeIDE -** -** Abstract : Linker script for STM32H7 series -** 1024Kbytes FLASH and 560Kbytes 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 : STMicroelectronics STM32 -** -** Distribution: The file is distributed as is, without any warranty -** of any kind. -** -***************************************************************************** -** @attention -** -** Copyright (c) 2022 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 */ -_sstack = ORIGIN(DTCMRAM); -_estack = ORIGIN(DTCMRAM) + LENGTH(DTCMRAM); /* end of RAM */ -/* Generate a link error if heap and stack don't fit into RAM/DTCM */ -_Min_Heap_Size = 0x200; /* required amount of heap */ -_Min_Stack_Size = 0x400; /* required amount of stack */ - -/* Specify the memory areas */ -MEMORY -{ - ITCMRAM (xrw) : ORIGIN = 0x00000000, LENGTH = 64K - DTCMRAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K - FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 1024K-128K-128K - FLASH_ST (rx) : ORIGIN = 0x080C0000, LENGTH = 128K - FLASH_BT (rx) : ORIGIN = 0x080E0000, LENGTH = 128K - RAM_D1 (xrw) : ORIGIN = 0x24000000, LENGTH = 320K - RAM_D2 (xrw) : ORIGIN = 0x30000000, LENGTH = 32K - RAM_D3 (xrw) : ORIGIN = 0x38000000, LENGTH = 16K -} - -/* Define output sections */ -SECTIONS -{ - /* Export Memory Layout Information for MPU Configuration */ - __itcm_base = ABSOLUTE(ORIGIN(ITCMRAM)); - __itcm_size = ABSOLUTE(LENGTH(ITCMRAM)); - __dtcm_base = ABSOLUTE(ORIGIN(DTCMRAM)); - __dtcm_size = ABSOLUTE(LENGTH(DTCMRAM)); - __flash_base = ABSOLUTE(ORIGIN(FLASH)); - __flash_size = ABSOLUTE(LENGTH(FLASH)); - __ram_d1_base = ABSOLUTE(ORIGIN(RAM_D1)); - __ram_d1_size = ABSOLUTE(LENGTH(RAM_D1)); - __ram_d2_base = ABSOLUTE(ORIGIN(RAM_D2)); - __ram_d2_size = ABSOLUTE(LENGTH(RAM_D2)); - __ram_d3_base = ABSOLUTE(ORIGIN(RAM_D3)); - __ram_d3_size = ABSOLUTE(LENGTH(RAM_D3)); - __peripheral_base = 0x40000000; - __peripheral_size = 0x20000000; /* 512MB */ - - /* The startup code goes first into FLASH */ - .isr_vector : - { - . = ALIGN(4); - KEEP(*(.isr_vector)) /* Startup code */ - . = ALIGN(4); - } >FLASH - - /* The program code and other data goes into FLASH */ - .text : - { - . = ALIGN(4); - _stext = .; - - *(.text) /* .text sections (code) */ - *(.text*) /* .text* sections (code) */ - *(.glue_7) /* glue arm to thumb code */ - *(.glue_7t) /* glue thumb to arm code */ - *(.eh_frame) - - KEEP (*(.init)) - KEEP (*(.fini)) - - . = ALIGN(4); - _etext = .; /* define a global symbols at end of code */ - } >FLASH - - /* Constant data goes into FLASH */ - .rodata : - { - . = ALIGN(4); - *(.rodata) /* .rodata sections (constants, strings, etc.) */ - *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ - . = ALIGN(4); - } >FLASH - - .hardfault_stack (NOLOAD) : /*Stack memory to avoid memfault inside hardfault handler*/ - { - . = ALIGN(8); - _hf_stack_start = .; - . += 0x400; /* 1 KB */ - _hf_stack_end = .; - } >DTCMRAM - - .ARM.extab (READONLY): { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH - .ARM (READONLY): { - __exidx_start = .; - *(.ARM.exidx*) - __exidx_end = .; - } >FLASH - - .preinit_array (READONLY): - { - PROVIDE_HIDDEN (__preinit_array_start = .); - KEEP (*(.preinit_array*)) - PROVIDE_HIDDEN (__preinit_array_end = .); - } >FLASH - - .init_array (READONLY): - { - PROVIDE_HIDDEN (__init_array_start = .); - KEEP (*(SORT(.init_array.*))) - KEEP (*(.init_array*)) - PROVIDE_HIDDEN (__init_array_end = .); - } >FLASH - - .fini_array (READONLY): - { - PROVIDE_HIDDEN (__fini_array_start = .); - KEEP (*(SORT(.fini_array.*))) - KEEP (*(.fini_array*)) - PROVIDE_HIDDEN (__fini_array_end = .); - } >FLASH - - /* MPU D1 Non-Cached Section: Placed at start of RAM_D1 for alignment */ - .mpu_ram_d1_nc (NOLOAD) : - { - . = ALIGN(32); - __mpu_d1_nc_start = ABSOLUTE(.); - - /* New MPU system buffers */ - *(.mpu_ram_d1_nc.buffer) - - /* User manual allocations via D1_NC macro */ - *(.mpu_ram_d1_nc.user) - - /* Ethernet Rx Pool */ - . = ALIGN(32); - *(.Rx_PoolSection) - } >RAM_D1 - - /* CALCULATE PADDING FOR MPU SUBREGIONS (D1) */ - _d1_size = SIZEOF(.mpu_ram_d1_nc); - /* Find next power of 2 (up to 512KB for 320KB RAM) */ - _d1_p2 = (1 << LOG2CEIL(MAX(32, _d1_size))); - /* Subregion size is RegionSize / 8 */ - _d1_sub = _d1_p2 / 8; - /* Align effective size to the subregion granularity */ - _d1_pad = (_d1_size + _d1_sub - 1) / _d1_sub * _d1_sub; - /* Advance current pointer to reserve this space */ - . = __mpu_d1_nc_start + _d1_pad; - __mpu_d1_nc_end = ABSOLUTE(.); - - /* 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 */ - } >DTCMRAM AT> FLASH - /* - .hard_fault_log has to be the first thing in the FLASH_ST - */ - - .hardfault_log : - { - . = ALIGN(4); - hf_log = .; - KEEP(*(.hardfault_log)); - . += 0x200; - } >FLASH_ST - - . = ALIGN(4); - - .metadata_pool : - { - . = ALIGN(4); - metadata = .; - KEEP(*(.metadata_pool)) - . += 0x100; - } >FLASH_ST - PROVIDE(_metadata = metadata); - PROVIDE(_hf_log = hf_log); - /* Uninitialized data section */ - . = ALIGN(4); - .bss (NOLOAD) : - { - /* This is used by the startup in order to initialize the .bss section */ - _sbss = .; /* define a global symbol at bss start */ - __bss_start__ = _sbss; - *(.bss) - *(.bss*) - *(COMMON) - - . = ALIGN(4); - _ebss = .; /* define a global symbol at bss end */ - __bss_end__ = _ebss; - } >DTCMRAM - - /* 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); - } >DTCMRAM - - /* MPU D2 Non-Cached Section: Contains Ethernet Descriptors and Generic Buffers */ - .mpu_ram_d2_nc (NOLOAD) : - { - . = ALIGN(32); - __mpu_d2_nc_start = ABSOLUTE(.); - - /* ETH Descriptors - Must be aligned */ - *(.RxDecripSection) - *(.TxDecripSection) - - /* New MPU system buffers */ - *(.mpu_ram_d2_nc.buffer) - - /* User manual allocations via D2_NC macro */ - *(.mpu_ram_d2_nc.user) - - } >RAM_D2 - - /* CALCULATE PADDING FOR MPU SUBREGIONS (D2) */ - _d2_size = SIZEOF(.mpu_ram_d2_nc); - /* Find next power of 2 (up to 64KB for 32KB RAM to catch overflow logic if needed) */ - _d2_p2 = (1 << LOG2CEIL(MAX(32, _d2_size))); - _d2_sub = _d2_p2 / 8; - _d2_pad = (_d2_size + _d2_sub - 1) / _d2_sub * _d2_sub; - . = __mpu_d2_nc_start + _d2_pad; - __mpu_d2_nc_end = ABSOLUTE(.); - - /* MPU D3 Non-Cached Section */ - .mpu_ram_d3_nc (NOLOAD) : - { - . = ALIGN(32); - __mpu_d3_nc_start = ABSOLUTE(.); - - /* New MPU system buffers */ - *(.mpu_ram_d3_nc.buffer) - - /* Legacy MPUManager allocations */ - *(.mpu_ram_d3_nc.legacy) - - /* User manual allocations via D3_NC macro */ - *(.mpu_ram_d3_nc.user) - - - } >RAM_D3 - - /* CALCULATE PADDING FOR MPU SUBREGIONS (D3) */ - _d3_size = SIZEOF(.mpu_ram_d3_nc); - /* Find next power of 2 (up to 32KB for 16KB RAM) */ - _d3_p2 = (1 << LOG2CEIL(MAX(32, _d3_size))); - _d3_sub = _d3_p2 / 8; - _d3_pad = (_d3_size + _d3_sub - 1) / _d3_sub * _d3_sub; - . = __mpu_d3_nc_start + _d3_pad; - __mpu_d3_nc_end = ABSOLUTE(.); - - /* Code running in ITCM RAM (0 Wait States, Instruction Bus) */ - .ram_code : - { - . = ALIGN(4); - _sram_code = .; - *(.ram_code) - *(.ram_code*) - . = ALIGN(4); - _eram_code = .; - } >ITCMRAM AT> FLASH - _siram_code = LOADADDR(.ram_code); - - /* Remove information from the standard libraries */ - /DISCARD/ : - { - libc.a ( * ) - libm.a ( * ) - libgcc.a ( * ) - } - - .ARM.attributes 0 : { *(.ARM.attributes) } - - /* MPU D1 Cached Section */ - .ram_d1 (NOLOAD) : - { - . = ALIGN(32); - - /* User manual allocations via D1_C macro */ - *(.ram_d1.user) - - /* New MPU system buffers */ - *(.ram_d1.buffer) - } >RAM_D1 - - /* MPU D2 Cached Section */ - .ram_d2 (NOLOAD) : - { - . = ALIGN(32); - - /* User manual allocations via D2_C macro */ - *(.ram_d2.user) - - /* New MPU system buffers */ - *(.ram_d2.buffer) - } >RAM_D2 - - /* MPU D3 Cached Section */ - .ram_d3 (NOLOAD) : - { - . = ALIGN(32); - - /* User manual allocations via D3_C macro */ - *(.ram_d3.user) - - /* New MPU system buffers */ - *(.ram_d3.buffer) - } >RAM_D3 -} diff --git a/STM32H723ZGTX_RAM.ld b/STM32H723ZGTX_RAM.ld deleted file mode 100644 index 8611972c3..000000000 --- a/STM32H723ZGTX_RAM.ld +++ /dev/null @@ -1,345 +0,0 @@ -/* -****************************************************************************** -** -** File : LinkerScript.ld (debug in RAM dedicated) -** -** Author : STM32CubeIDE -** -** Abstract : Linker script for STM32H7 series -** 320Kbytes RAM_EXEC and 240Kbytes 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 : STMicroelectronics STM32 -** -** Distribution: The file is distributed as is, without any warranty -** of any kind. -** -***************************************************************************** -** @attention -** -** Copyright (c) 2022 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. -** -**************************************************************************** -*/ - -/* This linker script places code and read-only data in ITCM RAM for execution - and places initialized data in DTCM RAM. This only leaves 64kB for code, so - it could potentially overflow, if you want to host a big application, maybe - should use RAM_D1 for code as well (and either adjust MPU settings or mess - arround with the memory areas specifications, so that the code thinks RAM_D1 - is actually FLASH). */ - -/* Entry Point */ -ENTRY(Reset_Handler) - - -/* Highest address of the user mode stack */ -_sstack = ORIGIN(DTCMRAM); -_estack = ORIGIN(DTCMRAM) + LENGTH(DTCMRAM); /* end of RAM */ -/* Generate a link error if heap and stack don't fit into RAM */ -_Min_Heap_Size = 0x200 ; /* required amount of heap */ -_Min_Stack_Size = 0x400 ; /* required amount of stack */ - -/* Specify the memory areas */ -MEMORY -{ - ITCMRAM (xrw) : ORIGIN = 0x00000000, LENGTH = 64K - DTCMRAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K - FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 1024K-128K - 128K - FLASH_ST (rx) : ORIGIN = 0x080C0000, LENGTH = 128K - FLASH_BT (rx) : ORIGIN = 0x080E0000, LENGTH = 128K - RAM_D1 (xrw) : ORIGIN = 0x24000000, LENGTH = 320K - RAM_D2 (xrw) : ORIGIN = 0x30000000, LENGTH = 32K - RAM_D3 (xrw) : ORIGIN = 0x38000000, LENGTH = 16K -} - -/* Define output sections */ -SECTIONS -{ - /* Export Memory Layout Information for MPU Configuration */ - __itcm_base = ABSOLUTE(ORIGIN(ITCMRAM)); - __itcm_size = ABSOLUTE(LENGTH(ITCMRAM)); - __dtcm_base = ABSOLUTE(ORIGIN(DTCMRAM)); - __dtcm_size = ABSOLUTE(LENGTH(DTCMRAM)); - __flash_base = ABSOLUTE(ORIGIN(FLASH)); - __flash_size = ABSOLUTE(LENGTH(FLASH)); - __ram_d1_base = ABSOLUTE(ORIGIN(RAM_D1)); - __ram_d1_size = ABSOLUTE(LENGTH(RAM_D1)); - __ram_d2_base = ABSOLUTE(ORIGIN(RAM_D2)); - __ram_d2_size = ABSOLUTE(LENGTH(RAM_D2)); - __ram_d3_base = ABSOLUTE(ORIGIN(RAM_D3)); - __ram_d3_size = ABSOLUTE(LENGTH(RAM_D3)); - __peripheral_base = 0x40000000; - __peripheral_size = 0x20000000; /* 512MB */ - - /* The startup code goes into ITCM for fastest access */ - .isr_vector : - { - . = ALIGN(4); - KEEP(*(.isr_vector)) /* Startup code */ - . = ALIGN(4); - } >ITCMRAM - - /* The program code goes into ITCM (instruction-optimized, 0 wait states) */ - .text : - { - . = ALIGN(4); - _stext = .; - - *(.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 */ - } >ITCMRAM - - /* Constant data goes into RAM_D1 (ITCM is too small for rodata) */ - .rodata : - { - . = ALIGN(4); - *(.rodata) /* .rodata sections (constants, strings, etc.) */ - *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ - . = ALIGN(4); - } >RAM_D1 - - .hardfault_stack (NOLOAD) : /*Stack memory to avoid memfault inside hardfault handler*/ - { - . = ALIGN(8); - _hf_stack_start = .; - . += 0x400; /* 1 KB */ - _hf_stack_end = .; - } >DTCMRAM - - .ARM.extab (READONLY): { *(.ARM.extab* .gnu.linkonce.armextab.*) } >RAM_D1 - .ARM (READONLY): { - __exidx_start = .; - *(.ARM.exidx*) - __exidx_end = .; - } >RAM_D1 - - .preinit_array (READONLY): - { - PROVIDE_HIDDEN (__preinit_array_start = .); - KEEP (*(.preinit_array*)) - PROVIDE_HIDDEN (__preinit_array_end = .); - } >RAM_D1 - - .init_array (READONLY): - { - PROVIDE_HIDDEN (__init_array_start = .); - KEEP (*(SORT(.init_array.*))) - KEEP (*(.init_array*)) - PROVIDE_HIDDEN (__init_array_end = .); - } >RAM_D1 - - .fini_array (READONLY): - { - PROVIDE_HIDDEN (__fini_array_start = .); - KEEP (*(SORT(.fini_array.*))) - KEEP (*(.fini_array*)) - PROVIDE_HIDDEN (__fini_array_end = .); - } >RAM_D1 - - /* MPU D1 Non-Cached Section */ - .mpu_ram_d1_nc (NOLOAD) : - { - . = ALIGN(32); - __mpu_d1_nc_start = ABSOLUTE(.); - - /* New MPU system buffers */ - *(.mpu_ram_d1_nc.buffer) - - /* User manual allocations via D1_NC macro */ - *(.mpu_ram_d1_nc.user) - - /* Ethernet Rx Pool */ - . = ALIGN(32); - *(.Rx_PoolSection) - } >RAM_D1 - - /* CALCULATE PADDING FOR MPU SUBREGIONS (D1) */ - _d1_size = SIZEOF(.mpu_ram_d1_nc); - /* Find next power of 2 */ - _d1_p2 = (1 << LOG2CEIL(MAX(32, _d1_size))); - /* Subregion size is RegionSize / 8 */ - _d1_sub = _d1_p2 / 8; - /* Align effective size to the subregion granularity */ - _d1_pad = (_d1_size + _d1_sub - 1) / _d1_sub * _d1_sub; - /* Advance current pointer to reserve this space */ - . = __mpu_d1_nc_start + _d1_pad; - __mpu_d1_nc_end = ABSOLUTE(.); - - - /* Initialized data sections goes into DTCM */ - .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 */ - } >DTCMRAM - - /* - .hard_fault_log has to be the first thing in the FLASH_ST - */ - - .hardfault_stack (NOLOAD) : /*Stack memory to avoid memfault inside hardfault handler*/ - { - . = ALIGN(8); - _hf_stack_start = .; - . += 0x400; /* 1 KB */ - _hf_stack_end = .; - } >DTCMRAM - /* Uninitialized data section */ - . = ALIGN(4); - .bss : - { - /* This is used by the startup in order to initialize the .bss section */ - _sbss = .; /* define a global symbol at bss start */ - __bss_start__ = _sbss; - *(.bss) - *(.bss*) - *(COMMON) - - . = ALIGN(4); - _ebss = .; /* define a global symbol at bss end */ - __bss_end__ = _ebss; - } >DTCMRAM - - /* 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); - } >DTCMRAM - - /* MPU D2 Non-Cached Section */ - .mpu_ram_d2_nc (NOLOAD) : - { - . = ALIGN(32); - __mpu_d2_nc_start = ABSOLUTE(.); - - /* Ethernet descriptors */ - *(.RxDecripSection) - *(.TxDecripSection) - - /* New MPU system buffers */ - *(.mpu_ram_d2_nc.buffer) - - /* User manual allocations via D2_NC macro */ - *(.mpu_ram_d2_nc.user) - } >RAM_D2 - - /* CALCULATE PADDING FOR MPU SUBREGIONS (D2) */ - _d2_size = SIZEOF(.mpu_ram_d2_nc); - /* Find next power of 2 */ - _d2_p2 = (1 << LOG2CEIL(MAX(32, _d2_size))); - _d2_sub = _d2_p2 / 8; - _d2_pad = (_d2_size + _d2_sub - 1) / _d2_sub * _d2_sub; - . = __mpu_d2_nc_start + _d2_pad; - __mpu_d2_nc_end = ABSOLUTE(.); - - /* MPU D3 Non-Cached Section */ - .mpu_ram_d3_nc (NOLOAD) : - { - . = ALIGN(32); - __mpu_d3_nc_start = ABSOLUTE(.); - - /* New MPU system buffers */ - *(.mpu_ram_d3_nc.buffer) - - /* Legacy MPUManager allocations */ - *(.mpu_ram_d3_nc.legacy) - - /* User manual allocations via D3_NC macro */ - *(.mpu_ram_d3_nc.user) - } >RAM_D3 - - /* CALCULATE PADDING FOR MPU SUBREGIONS (D3) */ - _d3_size = SIZEOF(.mpu_ram_d3_nc); - /* Find next power of 2 */ - _d3_p2 = (1 << LOG2CEIL(MAX(32, _d3_size))); - _d3_sub = _d3_p2 / 8; - _d3_pad = (_d3_size + _d3_sub - 1) / _d3_sub * _d3_sub; - . = __mpu_d3_nc_start + _d3_pad; - __mpu_d3_nc_end = ABSOLUTE(.); - - /* Additional code in ITCM, doesn't really do much with this configuration since everything is in ITCM anyways */ - .ram_code : - { - . = ALIGN(4); - _sram_code = .; - *(.ram_code) - *(.ram_code*) - . = ALIGN(4); - _eram_code = .; - } >ITCMRAM - - /* MPU D1 Cached Section */ - .ram_d1 (NOLOAD) : - { - . = ALIGN(32); - - /* New MPU system buffers */ - *(.ram_d1.buffer) - - /* User manual allocations via D1_C macro */ - *(.ram_d1.user) - } >RAM_D1 - - /* MPU D2 Cached Section */ - .ram_d2 (NOLOAD) : - { - . = ALIGN(32); - - /* New MPU system buffers */ - *(.ram_d2.buffer) - - /* User manual allocations via D2_C macro */ - *(.ram_d2.user) - } >RAM_D2 - - /* MPU D3 Cached Section */ - .ram_d3 (NOLOAD) : - { - . = ALIGN(32); - - /* New MPU system buffers */ - *(.ram_d3.buffer) - - /* User manual allocations via D3_C macro */ - *(.ram_d3.user) - } >RAM_D3 - - /* Remove information from the standard libraries */ - /DISCARD/ : - { - libc.a ( * ) - libm.a ( * ) - libgcc.a ( * ) - } - - .ARM.attributes 0 : { *(.ARM.attributes) } -} diff --git a/Src/HALAL/Models/MPUManager/MPUManager.cpp b/Src/HALAL/Models/MPUManager/MPUManager.cpp index b292298ae..6c0f14e1b 100644 --- a/Src/HALAL/Models/MPUManager/MPUManager.cpp +++ b/Src/HALAL/Models/MPUManager/MPUManager.cpp @@ -3,7 +3,7 @@ #ifdef SIM_ON alignas(32) uint8_t mpu_manager_memory_pool[NO_CACHED_RAM_MAXIMUM_SPACE]; #else -__attribute__((section(".mpu_ram_d3_nc.legacy"))) alignas(32 +__attribute__((section(".ram_d3_nc.legacy"))) alignas(32 ) volatile uint8_t mpu_manager_memory_pool[NO_CACHED_RAM_MAXIMUM_SPACE]; #endif diff --git a/Src/HALAL/Services/EXTI/EXTI.cpp b/Src/HALAL/Services/EXTI/EXTI.cpp index f4a4b7794..be99e2b60 100644 --- a/Src/HALAL/Services/EXTI/EXTI.cpp +++ b/Src/HALAL/Services/EXTI/EXTI.cpp @@ -1,10 +1,3 @@ -/* - * EXTI.cpp - * - * Created on: Nov 5, 2022 - * Author: alejandro - */ - #include "HALAL/Services/EXTI/EXTI.hpp" ST_LIB::EXTIDomain::Instance* ST_LIB::EXTIDomain::g_instances[ST_LIB::EXTIDomain::max_instances]; diff --git a/startup_stm32h723zgtx.s b/StartupCode.s similarity index 90% rename from startup_stm32h723zgtx.s rename to StartupCode.s index 0679cb4bb..3922118e3 100644 --- a/startup_stm32h723zgtx.s +++ b/StartupCode.s @@ -1,135 +1,90 @@ -/** - ****************************************************************************** - * @file startup_stm32h723xx.s - * @author MCD Application Team - * @brief STM32H723xx 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) 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. - * - ****************************************************************************** - */ - - .syntax unified - .cpu cortex-m7 - .fpu softvfp - .thumb +.syntax unified +.cpu cortex-m7 +.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 +.section .boot_code,"ax",%progbits .type Reset_Handler, %function Reset_Handler: - ldr sp, =_estack /* set stack pointer */ + ldr sp, =__estack /* set stack pointer */ + +/* Set VTOR to point to the relocated vector table in ITCMRAM */ + ldr r0, =0xE000ED08 /* VTOR Address */ + ldr r1, =__sisr_vector /* Address of the relocated vector table (0x00000000) */ + str r1, [r0] + +/* Call Configuration Checker function */ + bl ConfigurationChecker /* Call the clock system initialization function.*/ bl SystemInit -/* Copy the data segment initializers from flash to SRAM */ - ldr r0, =_sdata - ldr r1, =_edata - ldr r2, =_sidata - movs r3, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r4, [r2, r3] - str r4, [r0, r3] - adds r3, r3, #4 - -LoopCopyDataInit: - adds r4, r0, r3 - cmp r4, r1 - bcc CopyDataInit - -/* Copy the ram_code segment initializers from flash to ITCM */ - ldr r0, =_sram_code - ldr r1, =_eram_code - ldr r2, =_siram_code - movs r3, #0 - b LoopCopyRamCodeInit - -CopyRamCodeInit: - ldr r4, [r2, r3] - str r4, [r0, r3] - adds r3, r3, #4 - -LoopCopyRamCodeInit: - adds r4, r0, r3 - cmp r4, r1 - bcc CopyRamCodeInit - -/* Zero fill the bss segment. */ - ldr r2, =_sbss - ldr r4, =_ebss - movs r3, #0 - b LoopFillZerobss - -FillZerobss: - str r3, [r2] - adds r2, r2, #4 - -LoopFillZerobss: - cmp r2, r4 - bcc FillZerobss +/* Process Copy Table (Flash -> RAM) */ + ldr r4, =__copy_table_start + ldr r5, =__copy_table_end +.L_loop_copy_table: + cmp r4, r5 + beq .L_done_copy_table + ldmia r4!, {r1, r2, r3} /* r1=src, r2=dest_start, r3=dest_end */ +.L_loop_copy_section: + cmp r2, r3 + bge .L_next_copy_section + ldr r0, [r1], #4 + str r0, [r2], #4 + b .L_loop_copy_section +.L_next_copy_section: + b .L_loop_copy_table +.L_done_copy_table: + +/* Process Zero Table (BSS / Clear) */ + ldr r4, =__zero_table_start + ldr r5, =__zero_table_end + movs r0, #0 +.L_loop_zero_table: + cmp r4, r5 + beq .L_done_zero_table + ldmia r4!, {r1, r2} /* r1=dest_start, r2=dest_end */ +.L_loop_zero_section: + cmp r1, r2 + bge .L_next_zero_section + str r0, [r1], #4 + b .L_loop_zero_section +.L_next_zero_section: + b .L_loop_zero_table +.L_done_zero_table: + +/* Call board init (user defined function) */ + bl BoardInit /* Call static constructors */ - bl __libc_init_array + 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 +.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 M. Note that the proper constructs @@ -137,13 +92,13 @@ Infinite_Loop: * 0x0000.0000. * *******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors +.section .isr_vector,"a",%progbits +.type g_pfnVectors, %object +.size g_pfnVectors, .-g_pfnVectors g_pfnVectors: - .word _estack + .word __estack .word Reset_Handler .word NMI_Handler diff --git a/System.c b/System.c new file mode 100644 index 000000000..d02c623ab --- /dev/null +++ b/System.c @@ -0,0 +1,191 @@ +#define BOOT_ATTR __attribute__((section(".boot"))) __used + +#include "stm32h7xx.h" +#include + +#if !defined(HSE_VALUE) +#define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined(CSI_VALUE) +#define CSI_VALUE ((uint32_t)4000000) /*!< Value of the Internal oscillator in Hz*/ +#endif /* CSI_VALUE */ + +#if !defined(HSI_VALUE) +#define HSI_VALUE ((uint32_t)64000000) /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +uint32_t SystemCoreClock = 64000000; +uint32_t SystemD2Clock = 64000000; +const uint8_t D1CorePrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9}; + +BOOT_ATTR void SystemInit(void) { + __IO uint32_t tmpreg; + + SCB->CPACR |= ((3UL << (10 * 2)) | (3UL << (11 * 2))); /* set CP10 and CP11 Full Access */ + /* Reset the RCC clock configuration to the default reset state ------------*/ + + /* Increasing the CPU frequency */ + if (FLASH_LATENCY_DEFAULT > (READ_BIT((FLASH->ACR), FLASH_ACR_LATENCY))) { + /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */ + MODIFY_REG(FLASH->ACR, FLASH_ACR_LATENCY, (uint32_t)(FLASH_LATENCY_DEFAULT)); + } + + /* Set HSION bit */ + RCC->CR |= RCC_CR_HSION; + + /* Reset CFGR register */ + RCC->CFGR = 0x00000000; + + /* Reset HSEON, HSECSSON, CSION, HSI48ON, CSIKERON, PLL1ON, PLL2ON and PLL3ON bits */ + RCC->CR &= 0xEAF6ED7FU; + + /* Decreasing the number of wait states because of lower CPU frequency */ + if (FLASH_LATENCY_DEFAULT < (READ_BIT((FLASH->ACR), FLASH_ACR_LATENCY))) { + /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */ + MODIFY_REG(FLASH->ACR, FLASH_ACR_LATENCY, (uint32_t)(FLASH_LATENCY_DEFAULT)); + } + + /* Reset D1CFGR register */ + RCC->D1CFGR = 0x00000000; + + /* Reset D2CFGR register */ + RCC->D2CFGR = 0x00000000; + + /* Reset D3CFGR register */ + RCC->D3CFGR = 0x00000000; + + /* Reset PLLCKSELR register */ + RCC->PLLCKSELR = 0x02020200; + + /* Reset PLLCFGR register */ + RCC->PLLCFGR = 0x01FF0000; + /* Reset PLL1DIVR register */ + RCC->PLL1DIVR = 0x01010280; + /* Reset PLL1FRACR register */ + RCC->PLL1FRACR = 0x00000000; + + /* Reset PLL2DIVR register */ + RCC->PLL2DIVR = 0x01010280; + + /* Reset PLL2FRACR register */ + + RCC->PLL2FRACR = 0x00000000; + /* Reset PLL3DIVR register */ + RCC->PLL3DIVR = 0x01010280; + + /* Reset PLL3FRACR register */ + RCC->PLL3FRACR = 0x00000000; + + /* Reset HSEBYP bit */ + RCC->CR &= 0xFFFBFFFFU; + + /* Disable all interrupts */ + RCC->CIER = 0x00000000; + + RCC->AHB2ENR |= (RCC_AHB2ENR_D2SRAM1EN | RCC_AHB2ENR_D2SRAM2EN); + + tmpreg = RCC->AHB2ENR; + (void)tmpreg; + + /* + * Disable the FMC bank1 (enabled after reset). + * This, prevents CPU speculation access on this bank which blocks the use of FMC during + * 24us. During this time the others FMC master (such as LTDC) cannot use it! + */ + FMC_Bank1_R->BTCR[0] = 0x000030D2; +} + + +BOOT_ATTR void SystemCoreClockUpdate(void) { + uint32_t pllp, pllsource, pllm, pllfracen, hsivalue, tmp; + uint32_t common_system_clock; + float_t fracn1, pllvco; + + /* Get SYSCLK source -------------------------------------------------------*/ + + switch (RCC->CFGR & RCC_CFGR_SWS) { + case RCC_CFGR_SWS_HSI: /* HSI used as system clock source */ + common_system_clock = (uint32_t)(HSI_VALUE >> ((RCC->CR & RCC_CR_HSIDIV) >> 3)); + break; + + case RCC_CFGR_SWS_CSI: /* CSI used as system clock source */ + common_system_clock = CSI_VALUE; + break; + + case RCC_CFGR_SWS_HSE: /* HSE used as system clock source */ + common_system_clock = HSE_VALUE; + break; + + case RCC_CFGR_SWS_PLL1: /* PLL1 used as system clock source */ + + /* PLL_VCO = (HSE_VALUE or HSI_VALUE or CSI_VALUE/ PLLM) * PLLN + SYSCLK = PLL_VCO / PLLR + */ + pllsource = (RCC->PLLCKSELR & RCC_PLLCKSELR_PLLSRC); + pllm = ((RCC->PLLCKSELR & RCC_PLLCKSELR_DIVM1) >> 4); + pllfracen = ((RCC->PLLCFGR & RCC_PLLCFGR_PLL1FRACEN) >> RCC_PLLCFGR_PLL1FRACEN_Pos); + fracn1 = (float_t)(uint32_t)(pllfracen * ((RCC->PLL1FRACR & RCC_PLL1FRACR_FRACN1) >> 3)); + + if (pllm != 0U) { + switch (pllsource) { + case RCC_PLLCKSELR_PLLSRC_HSI: /* HSI used as PLL clock source */ + + hsivalue = (HSI_VALUE >> ((RCC->CR & RCC_CR_HSIDIV) >> 3)); + pllvco = ((float_t)hsivalue / (float_t)pllm) * + ((float_t)(uint32_t)(RCC->PLL1DIVR & RCC_PLL1DIVR_N1) + + (fracn1 / (float_t)0x2000) + (float_t)1); + + break; + + case RCC_PLLCKSELR_PLLSRC_CSI: /* CSI used as PLL clock source */ + pllvco = ((float_t)CSI_VALUE / (float_t)pllm) * + ((float_t)(uint32_t)(RCC->PLL1DIVR & RCC_PLL1DIVR_N1) + + (fracn1 / (float_t)0x2000) + (float_t)1); + break; + + case RCC_PLLCKSELR_PLLSRC_HSE: /* HSE used as PLL clock source */ + pllvco = ((float_t)HSE_VALUE / (float_t)pllm) * + ((float_t)(uint32_t)(RCC->PLL1DIVR & RCC_PLL1DIVR_N1) + + (fracn1 / (float_t)0x2000) + (float_t)1); + break; + + default: + hsivalue = (HSI_VALUE >> ((RCC->CR & RCC_CR_HSIDIV) >> 3)); + pllvco = ((float_t)hsivalue / (float_t)pllm) * + ((float_t)(uint32_t)(RCC->PLL1DIVR & RCC_PLL1DIVR_N1) + + (fracn1 / (float_t)0x2000) + (float_t)1); + break; + } + pllp = (((RCC->PLL1DIVR & RCC_PLL1DIVR_P1) >> 9) + 1U); + common_system_clock = (uint32_t)(float_t)(pllvco / (float_t)pllp); + } else { + common_system_clock = 0U; + } + break; + + default: + common_system_clock = (uint32_t)(HSI_VALUE >> ((RCC->CR & RCC_CR_HSIDIV) >> 3)); + break; + } + + tmp = D1CorePrescTable[(RCC->D1CFGR & RCC_D1CFGR_D1CPRE) >> RCC_D1CFGR_D1CPRE_Pos]; + + /* common_system_clock frequency : CM7 CPU frequency */ + common_system_clock >>= tmp; + + /* SystemD2Clock frequency : CM4 CPU, AXI and AHBs Clock frequency */ + SystemD2Clock = + (common_system_clock >> + ((D1CorePrescTable[(RCC->D1CFGR & RCC_D1CFGR_HPRE) >> RCC_D1CFGR_HPRE_Pos]) & 0x1FU)); + + SystemCoreClock = common_system_clock; +} + +__attribute__((weak)) BOOT_ATTR void ConfigurationChecker() { + // Nothing for now +} + +__attribute__((weak)) void BoardInit(void) { + // do nothing by default +}