From d554ade7cea7c43f54c46f30032b1779c140b229 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Mon, 15 Jan 2024 14:32:17 -0600 Subject: [PATCH] AP_IOMCU: match thread stack pointer types to ChibiOS `__main_thread_stack_base__` and `__main_thread_stack_end__` are variables whose address is defined to be the corresponding part of the stack. These are declared as `extern stkalign_t` in ChibiOS code, and being declared as `extern uint32_t` in ArduPilot code creates a warning at link time when using LTO. Correct the declaration to eliminate this warning. Also update `__main_stack_base__` and `__main_stack_end__` which don't currently trigger this warning but serve similar purposes and so might in the future. The hardware expects an alignment of `stkalign_t` (which is 8 bytes) and the linker script defines the variable values with this alignment as well, so this is safe. No code size or functional change. --- libraries/AP_IOMCU/iofirmware/iofirmware.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp index 2b1e65d145..6e97fa4cf2 100644 --- a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp +++ b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp @@ -341,8 +341,8 @@ void AP_IOMCU_FW::init() #if CH_DBG_ENABLE_STACK_CHECK == TRUE static void stackCheck(uint16_t& mstack, uint16_t& pstack) { - extern uint32_t __main_stack_base__[]; - extern uint32_t __main_stack_end__[]; + extern stkalign_t __main_stack_base__[]; + extern stkalign_t __main_stack_end__[]; uint32_t stklimit = (uint32_t)__main_stack_end__; uint32_t stkbase = (uint32_t)__main_stack_base__; uint32_t *crawl = (uint32_t *)stkbase; @@ -354,8 +354,8 @@ static void stackCheck(uint16_t& mstack, uint16_t& pstack) { chDbgAssert(free > 0, "mstack exhausted"); mstack = (uint16_t)free; - extern uint32_t __main_thread_stack_base__[]; - extern uint32_t __main_thread_stack_end__[]; + extern stkalign_t __main_thread_stack_base__[]; + extern stkalign_t __main_thread_stack_end__[]; stklimit = (uint32_t)__main_thread_stack_end__; stkbase = (uint32_t)__main_thread_stack_base__; crawl = (uint32_t *)stkbase;