Use the command . /waf configure --board=CUAVv5 && . /waf copter the cross compiler used is arm-none-eabi-gcc. I would like to know which libraries for the target platform arupilot depends on during compilation? Where can I find those informations?
Since I want to use Clang to perform the cross-compilation process, I need to specify the libraries that ardupilot depends on with “-I”.
I used grep to find if there was any info about clang in ./waf configure like so:
$ ./waf configure --help
...
--check-cxx-compiler=CHECK_CXX_COMPILER
list of C++ compilers to try [g++ clang++ icpc]
--check-c-compiler=CHECK_C_COMPILER
list of C compilers to try [gcc clang icc]
Thus:
$ ./waf configure --board=CUAVv5 --check-cxx-compiler=clang++ --check-c-compiler=clang && ./waf copter
Setting top to : /home/ryan/Dev/ros2_ws/src/ardupilot
Setting out to : /home/ryan/Dev/ros2_ws/src/ardupilot/build
Autoconfiguration : enabled
Checking for program 'python' : /usr/bin/python3
Checking for python version >= 3.6.9 : 3.10.12
Setting board to : CUAVv5
Using toolchain : arm-none-eabi
Checking for 'clang++' (C++ compiler) : not found
could not configure a C++ compiler!
(complete log in /home/ryan/Dev/ros2_ws/src/ardupilot/build/config.log)
To install clang on ubuntu 22, I did the following, which installed clang 14.
$ sudo apt install clang
That got passed the configure phase, but there was a build failure.
$ ./waf configure --board=CUAVv5 --check-cxx-compiler=clang++ --check-c-compiler=clang && ./waf copter
Setting top to : /home/ryan/Dev/ros2_ws/src/ardupilot
Setting out to : /home/ryan/Dev/ros2_ws/src/ardupilot/build
Autoconfiguration : enabled
Checking for program 'python' : /usr/bin/python3
Checking for python version >= 3.6.9 : 3.10.12
Setting board to : CUAVv5
Using toolchain : arm-none-eabi
Checking for 'clang++' (C++ compiler) : /usr/lib/ccache/clang++
Checking for 'clang' (C compiler) : /usr/lib/ccache/clang
Checking for c flags '-MMD' : yes
Checking for cxx flags '-MMD' : yes
CXX Compiler : clang++ 14.0.0
Checking for program 'make' : /usr/bin/make
Checking for program 'arm-none-eabi-objcopy' : /opt/gcc-arm-none-eabi-10-2020-q4-major/bin/arm-none-eabi-objcopy
Including /home/ryan/Dev/ros2_ws/src/ardupilot/libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat
Adding environment OPTIMIZE -O2
Removing HAL_GPIO_A_LED_PIN
Removing HAL_GPIO_B_LED_PIN
Removing IMU
Removing PF11
Setup for MCU STM32F767xx
Writing hwdef setup in /home/ryan/Dev/ros2_ws/src/ardupilot/build/CUAVv5/hwdef.h
MCU Flags: cortex-m7 ['-mcpu=cortex-m7', '-mfpu=fpv5-d16', '-mfloat-abi=hard']
Writing DMA map
Setting up as normal
No change in hwdef.h
Generating ldscript.ld
No default parameter file found
Checking for env.py
env set OPTIMIZE=-O2
env set ENABLE_DFU_BOOT=0
env set WITH_FATFS=1
env set WITH_NETWORKING=False
env set PROCESS_STACK=0x1C00
env set MAIN_STACK=0x600
env set IOMCU_FW=0
env set PERIPH_FW=0
env set HAL_NUM_CAN_IFACES=2
env set HAL_CANFD_SUPPORTED=0
env set BOARD_FLASH_SIZE=2048
env set EXT_FLASH_SIZE_MB=0
env set INT_FLASH_PRIMARY=False
env set ENABLE_CRASHDUMP=True
env set APP_RAM_START=None
env set CPU_FLAGS=['-mcpu=cortex-m7', '-mfpu=fpv5-d16', '-mfloat-abi=hard', '-DARM_MATH_CM7', '-u_printf_float']
env set CORTEX=cortex-m7
env set APJ_BOARD_ID=50
env set APJ_BOARD_TYPE=STM32F767xx
env set USBID=0x1209/0x5740
env set FLASH_RESERVE_START_KB=32
env set EXT_FLASH_RESERVE_START_KB=0
env set FLASH_TOTAL=2064384
env set HAS_EXTERNAL_FLASH_SECTIONS=0
env set CHIBIOS_BUILD_FLAGS=USE_FATFS=yes USE_LWIP=no CHIBIOS_STARTUP_MK=os/common/startup/ARMCMx/compilers/GCC/mk/startup_stm32f7xx.mk CHIBIOS_PLATFORM_MK=os/hal/ports/STM32/STM32F7xx/platform.mk MCU=cortex-m7 ENV_UDEFS=-DCHPRINTF_USE_FLOAT=1
Enabling ChibiOS asserts : no
Disabling Watchdog : no
Enabling malloc guard : no
Enabling ChibiOS thread statistics : no
Enabling -Werror : no
Checking for intelhex module: : OK
Enabled OpenDroneID : no
Enabled firmware ID checking : no
GPS Debug Logging : no
Enabled custom controller : no
Checking for HAVE_CMATH_ISFINITE : no
Checking for HAVE_CMATH_ISINF : no
Checking for HAVE_CMATH_ISNAN : no
Checking for NEED_CMATH_ISFINITE_STD_NAMESPACE : no
Checking for NEED_CMATH_ISINF_STD_NAMESPACE : no
Checking for NEED_CMATH_ISNAN_STD_NAMESPACE : no
Checking for header endian.h : not found
Checking for header byteswap.h : not found
Checking for HAVE_MEMRCHR : no
Configured VSCode Intellisense: : no
DC_DSDL compiler : /home/ryan/Dev/ros2_ws/src/ardupilot/modules/DroneCAN/dronecan_dsdlc/dronecan_dsdlc.py
Source is git repository : yes
Update submodules : yes
Checking for program 'git' : /usr/bin/git
Gtest : STM32 boards currently don't support compiling gtest
Checking for program 'arm-none-eabi-size' : /opt/gcc-arm-none-eabi-10-2020-q4-major/bin/arm-none-eabi-size
Benchmarks : disabled
Unit tests : disabled
Scripting : maybe
Scripting runtime checks : enabled
Debug build : disabled
Coverage build : disabled
Force 32-bit build : disabled
Checking for program 'rsync' : /usr/bin/rsync
'configure' finished successfully (0.751s)
Waf: Entering directory `/home/ryan/Dev/ros2_ws/src/ardupilot/build/CUAVv5'
Checking for env.py
env added OPTIMIZE=-O2
env added ENABLE_DFU_BOOT=0
env added WITH_FATFS=1
env added WITH_NETWORKING=False
env added PROCESS_STACK=0x1C00
env added MAIN_STACK=0x600
env added IOMCU_FW=0
env added PERIPH_FW=0
env added HAL_NUM_CAN_IFACES=2
env added HAL_CANFD_SUPPORTED=0
env added BOARD_FLASH_SIZE=2048
env added EXT_FLASH_SIZE_MB=0
env added INT_FLASH_PRIMARY=False
env added ENABLE_CRASHDUMP=True
env appended APP_RAM_START=None
env appended CPU_FLAGS=['-mcpu=cortex-m7', '-mfpu=fpv5-d16', '-mfloat-abi=hard', '-DARM_MATH_CM7', '-u_printf_float']
env added CORTEX=cortex-m7
env added APJ_BOARD_ID=50
env added APJ_BOARD_TYPE=STM32F767xx
env added USBID=0x1209/0x5740
env added FLASH_RESERVE_START_KB=32
env added EXT_FLASH_RESERVE_START_KB=0
env added FLASH_TOTAL=2064384
env added HAS_EXTERNAL_FLASH_SECTIONS=0
env added CHIBIOS_BUILD_FLAGS=USE_FATFS=yes USE_LWIP=no CHIBIOS_STARTUP_MK=os/common/startup/ARMCMx/compilers/GCC/mk/startup_stm32f7xx.mk CHIBIOS_PLATFORM_MK=os/hal/ports/STM32/STM32F7xx/platform.mk MCU=cortex-m7 ENV_UDEFS=-DCHPRINTF_USE_FLOAT=1
Padded 8 bytes for bootloader.bin to 16448
Embedding file bootloader.bin:/home/ryan/Dev/ros2_ws/src/ardupilot/Tools/bootloaders/CUAVv5_bl.bin
Embedding file hwdef.dat:/home/ryan/Dev/ros2_ws/src/ardupilot/build/CUAVv5/hw.dat
Embedding file io_firmware.bin:Tools/IO_Firmware/iofirmware_lowpolh.bin
Embedding file io_firmware_dshot.bin:Tools/IO_Firmware/iofirmware_dshot_lowpolh.bin
[ 12/1081] Compiling libraries/AC_AttitudeControl/ControlMonitor.cpp
[ 13/1081] Compiling libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.cpp
[ 14/1081] Compiling libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp
[ 15/1081] Compiling libraries/AC_AttitudeControl/AC_CommandModel.cpp
[ 16/1081] Compiling libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp
[ 17/1081] Compiling libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp
[ 18/1081] Compiling libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp
[ 19/1081] Compiling libraries/AC_AutoTune/AC_AutoTune_Multi.cpp
[ 20/1081] Compiling libraries/AC_AutoTune/AC_AutoTune_Heli.cpp
[ 21/1081] Compiling libraries/AC_AutoTune/AC_AutoTune_FreqResp.cpp
[ 22/1081] Compiling libraries/AC_Autorotation/AC_Autorotation.cpp
[ 23/1081] Compiling libraries/AC_Avoidance/AP_OAVisGraph.cpp
[ 24/1081] Compiling libraries/AC_Avoidance/AP_OAPathPlanner.cpp
[ 25/1081] Compiling libraries/AC_Avoidance/AP_OADijkstra.cpp
[ 26/1081] Compiling libraries/AC_Avoidance/AC_Avoidance_Logging.cpp
[ 27/1081] Compiling libraries/AC_InputManager/AC_InputManager_Heli.cpp
[ 28/1081] Compiling libraries/AC_InputManager/AC_InputManager.cpp
[ 29/1081] Compiling libraries/AC_PID/AC_P_2D.cpp
[ 30/1081] Compiling libraries/AC_PID/AC_P_1D.cpp
[ 31/1081] Compiling libraries/AC_PID/AC_PI_2D.cpp
[ 32/1081] Compiling libraries/AC_PID/AC_PID_Basic.cpp
[ 33/1081] Compiling libraries/AC_PID/AC_PID_2D.cpp
[ 34/1081] Compiling libraries/AC_PID/AC_PID.cpp
[ 35/1081] Compiling libraries/AC_PID/AC_PI.cpp
[ 36/1081] Compiling libraries/AC_PID/AC_P.cpp
[ 37/1081] Compiling libraries/AC_PID/AC_HELI_PID.cpp
[ 38/1081] Compiling libraries/AC_PrecLand/AC_PrecLand_StateMachine.cpp
[ 39/1081] Compiling libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.cpp
[ 40/1081] Compiling libraries/AC_PrecLand/AC_PrecLand_SITL.cpp
[ 41/1081] Compiling libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp
[ 42/1081] Compiling libraries/AC_PrecLand/AC_PrecLand_Companion.cpp
[ 43/1081] Compiling libraries/AC_PrecLand/PosVelEKF.cpp
clang: fatal error: unknown argument: '-mno-thumb-interwork'
Waf already handles includes for you, like in the wscript file below. You should be using waf to build, not invoking the compiler directly.
Thanks for your suggestion, “clang: fatal error: unknown argument: ‘-mno-thumb-interwork’” can be solved by deleting the -mno-thumb-interwork contained in the CXXFLAGS list in the build/CUAVv5_cache.py file. in the CXXFLAGS list in the build/CUAVv5_cache.py file.