diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef.dat index bad4197e5e..13538e105f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef.dat @@ -15,6 +15,8 @@ MCU_CLOCKRATE_MHZ 480 env OPTIMIZE -O2 +define HAL_WITH_EKF_DOUBLE 0 + STM32_ST_USE_TIMER 2 # internal flash is off limits diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf.ld b/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf.ld index 4aec753fb9..87423bd42d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf.ld +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf.ld @@ -135,6 +135,7 @@ SECTIONS lib/lib*.a:*Filter.*(.text* .rodata*) lib/lib*.a:*Filter2p.*(.text* .rodata*) lib/lib*.a:SPIDevice.*(.text* .rodata*) + lib/lib*.a:I2CDevice.*(.text* .rodata*) lib/lib*.a:Util.*(.text* .rodata*) lib/lib*.a:Device.*(.text* .rodata*) lib/lib*.a:Scheduler.*(.text* .rodata*) @@ -143,8 +144,15 @@ SECTIONS lib/lib*.a:crc.*(.text* .rodata*) lib/lib*.a:matrixN.*(.text* .rodata*) lib/lib*.a:matrix_alg.*(.text* .rodata*) - lib/lib*.a:AP_NavEKF*.*(.text* .rodata*) - lib/lib*.a:EKFGSF*.*(.text* .rodata*) + lib/lib*.a:AP_NavEKF3*.*(.text* .rodata*) + lib/lib*.a:AP_NavEKF_*.*(.text* .rodata*) + lib/lib*.a:EKF*.*(.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:vector2.*(.text* .rodata*) lib/lib*.a:quaternion.*(.text* .rodata*) lib/lib*.a:polygon.*(.text* .rodata*)