From 13ca44423d1290dae0907085c5b973f244e3a5b9 Mon Sep 17 00:00:00 2001 From: Martin Luessi Date: Thu, 1 Jun 2023 12:30:48 -0700 Subject: [PATCH] AP_HAL_ChibiOS: Move more time critical code to RAM for H750 --- .../hwdef/common/common_extf_h750.ld | 17 +++++++++++++++-- 1 file changed, 15 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf_h750.ld b/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf_h750.ld index 2ff9ede68e..f5279e4c71 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf_h750.ld +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf_h750.ld @@ -125,6 +125,8 @@ SECTIONS /**libg_nano.a:*memset*(.text*) *libg_nano.a:*memcpy*(.text*)*/ *libm.a:*(.text*) + *libc_nano.a:*memcpy*(.text*) + *libgcc.a:*(.text*) /* For some reason boards won't boot if libc is in RAM, but will with debug on */ /**libc_nano.a:*(.text* .rodata*) *libstdc++_nano.a:(.text* .rodata*)*/ @@ -154,6 +156,7 @@ SECTIONS lib/lib*.a:*Filter2p.*(.text* .rodata*) lib/lib*.a:SPIDevice.*(.text* .rodata*) lib/lib*.a:I2CDevice.*(.text* .rodata*) + lib/lib*.a:UARTDriver.*(.text* .rodata*) lib/lib*.a:Util.*(.text* .rodata*) lib/lib*.a:Device.*(.text* .rodata*) lib/lib*.a:Scheduler.*(.text* .rodata*) @@ -164,13 +167,20 @@ SECTIONS lib/lib*.a:matrix_alg.*(.text* .rodata*) lib/lib*.a:AP_NavEKF3*.*(.text* .rodata*) lib/lib*.a:AP_NavEKF_*.*(.text* .rodata*) + lib/lib*.a:AP_AHRS*.*(.text* .rodata*) lib/lib*.a:EKF*.*(.text* .rodata*) + lib/lib*.a:AP_Scheduler.*(.text* .rodata*) + lib/lib*.a:AP_InertialSensor*(.text* .rodata*) lib/lib*.a:AP_Compass_Backend.*(.text* .rodata*) lib/lib*.a:AP_RCProtocol_Backend.*(.text* .rodata*) lib/lib*.a:AP_RCProtocol.*(.text* .rodata*) lib/lib*.a:AP_RCProtocol_CRSF.*(.text* .rodata*) lib/lib*.a:AP_RCTelemetry.*(.text* .rodata*) lib/lib*.a:AP_CRSF_Telem.*(.text* .rodata*) + lib/lib*.a:AP_MotorsMatrix.*(.text* .rodata*) + lib/lib*.a:RC_Channel.*(.text* .rodata*) + lib/lib*.a:RCInput.*(.text* .rodata*) + lib/lib*.a:RCOutput.*(.text* .rodata*) lib/lib*.a:vector2.*(.text* .rodata*) lib/lib*.a:quaternion.*(.text* .rodata*) lib/lib*.a:polygon.*(.text* .rodata*) @@ -178,6 +188,8 @@ SECTIONS /* uncomment these to test CPUInfo in FLASH_RAM */ /*Tools/CPUInfo/CPUInfo.*(.text* .rodata*) Tools/CPUInfo/EKF_Maths.*(.text* .rodata*)*/ + lib/lib*.a:AC_AttitudeControl*.*(.text* .rodata*) + lib/lib*.a:AC_PID*.*(.text* .rodata*) *(.ramfunc*) . = ALIGN(4); } > flashram AT > default_flash @@ -216,6 +228,7 @@ SECTIONS lib/lib*.a:vector3.*(.rodata*) lib/lib*.a:matrix3.*(.rodata*) *libm.a:*(.rodata*) + ArduCopter/Copter.*(.rodata*) *(.ramdata*) . = ALIGN(4); } > dataram AT > default_flash @@ -253,13 +266,13 @@ SECTIONS .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) - } > default_flash + } > instram AT > default_flash .ARM.exidx : { __exidx_start = .; *(.ARM.exidx* .gnu.linkonce.armexidx.*) __exidx_end = .; - } > default_flash + } > instram AT > default_flash .eh_frame_hdr : {