Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_HAL_ChibiOS: External flash optimizations (H750 etc.) backport to 4.4 #24098

Merged
merged 16 commits into from Sep 6, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
Binary file modified Tools/bootloaders/DevEBoxH7v2_bl.bin
Binary file not shown.
3,311 changes: 1,660 additions & 1,651 deletions Tools/bootloaders/DevEBoxH7v2_bl.hex

Large diffs are not rendered by default.

Binary file modified Tools/bootloaders/SPRacingH7_bl.bin
Binary file not shown.
3,127 changes: 1,568 additions & 1,559 deletions Tools/bootloaders/SPRacingH7_bl.hex

Large diffs are not rendered by default.

485 changes: 387 additions & 98 deletions Tools/scripts/size_compare_branches.py

Large diffs are not rendered by default.

4 changes: 4 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk
Expand Up @@ -250,6 +250,10 @@ endif
# Define ASM defines here
UADEFS =

ifeq ($(COPY_VECTORS_TO_RAM),yes)
UADEFS += -DCRT0_INIT_VECTORS=1
endif

# List all user directories here
UINCDIR =

Expand Down
52 changes: 33 additions & 19 deletions libraries/AP_HAL_ChibiOS/hwdef/common/common_extf.ld
Expand Up @@ -20,16 +20,16 @@
*/

/* RAM region to be used for fast code. */
REGION_ALIAS("FASTCODE_RAM", ram1)
REGION_ALIAS("FASTCODE_RAM", flashram)

/* stack areas are configured to be in AXI RAM (ram1) to ensure the SSBL will load the image */
/* RAM region to be used for Main stack. This stack accommodates the processing
of all exceptions and interrupts*/
REGION_ALIAS("MAIN_STACK_RAM", ram1);
REGION_ALIAS("MAIN_STACK_RAM", flashram);

/* RAM region to be used for the process stack. This is the stack used by
the main() function.*/
REGION_ALIAS("PROCESS_STACK_RAM", ram1);
REGION_ALIAS("PROCESS_STACK_RAM", flashram);

/* RAM region to be used for data segment.*/
REGION_ALIAS("DATA_RAM", ram0);
Expand All @@ -45,19 +45,19 @@ __ram0_size__ = LENGTH(ram0);
__ram0_end__ = __ram0_start__ + __ram0_size__;

/* AXI */
__ram1_start__ = ORIGIN(ram1);
__ram1_size__ = LENGTH(ram1);
__ram1_start__ = ORIGIN(flashram);
__ram1_size__ = LENGTH(flashram);
__ram1_end__ = __ram1_start__ + __ram1_size__;

/* DTCM */
__ram2_start__ = ORIGIN(ram2);
__ram2_size__ = LENGTH(ram2);
__ram2_start__ = ORIGIN(dataram);
__ram2_size__ = LENGTH(dataram);
__ram2_end__ = __ram2_start__ + __ram2_size__;

/* ITCM */
__instram_start__ = ORIGIN(instram);
__instram_size__ = LENGTH(instram);
__instram_end__ = __instram_start__ + __instram_size__;
__ram3_start__ = ORIGIN(instram);
__ram3_size__ = LENGTH(instram);
__ram3_end__ = __ram3_start__ + __ram3_size__;

ENTRY(Reset_Handler)

Expand All @@ -66,10 +66,14 @@ SECTIONS
. = 0;
_text = .;

startup : ALIGN(16) SUBALIGN(16)
/* Vector table: copied to RAM by startup script */
vectors : ALIGN(1024) SUBALIGN(16)
{
__textvectors_base__ = LOADADDR(vectors);
__vectors_base__ = .;
KEEP(*(.vectors))
} > default_flash
__vectors_end__ = .;
} > dataram AT > default_flash

constructors : ALIGN(4) SUBALIGN(4)
{
Expand All @@ -91,8 +95,8 @@ SECTIONS
.fastramfunc : ALIGN(4) SUBALIGN(4)
{
. = ALIGN(4);
__instram_init_text__ = LOADADDR(.fastramfunc);
__instram_init__ = .;
__ram3_init_text__ = LOADADDR(.fastramfunc);
__ram3_init__ = .;
/* ChibiOS won't boot unless these are excluded */
EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o)
/* performance critical sections of ChibiOS */
Expand All @@ -119,9 +123,19 @@ SECTIONS
*libstdc++_nano.a:(.text* .rodata*)*/
*(.fastramfunc)
. = ALIGN(4);
__instram_end__ = .;
} > instram AT > default_flash

.ram3 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram3_clear__ = .;
. = ALIGN(4);
__ram3_noinit__ = .;
. = ALIGN(4);
__ram3_free__ = .;
. = ALIGN(4);
} > instram

/* FLASH_RAM area is primarily used for RAM-based code and data, 256k allocation on H7 */
.ramfunc : ALIGN(4) SUBALIGN(4)
{
Expand Down Expand Up @@ -162,7 +176,7 @@ SECTIONS
Tools/CPUInfo/EKF_Maths.*(.text* .rodata*)*/
*(.ramfunc*)
. = ALIGN(4);
} > ram1 AT > default_flash
} > flashram AT > default_flash

.ram1 (NOLOAD) : ALIGN(4)
{
Expand All @@ -173,7 +187,7 @@ SECTIONS
*(.ram1*)
. = ALIGN(4);
__ram1_free__ = .;
} > ram1
} > flashram

/* DATA_RAM area is DTCM primarily used for RAM-based data, e.g. vtables */
.ramdata : ALIGN(4)
Expand Down Expand Up @@ -201,7 +215,7 @@ SECTIONS
*libm.a:*(.rodata*)
*(.ramdata*)
. = ALIGN(4);
} > ram2 AT > default_flash
} > dataram AT > default_flash

.ram2 (NOLOAD) : ALIGN(4)
{
Expand All @@ -212,7 +226,7 @@ SECTIONS
*(.ram2*)
. = ALIGN(4);
__ram2_free__ = .;
} > ram2
} > dataram

.text : ALIGN(4) SUBALIGN(4)
{
Expand Down