Secure bootloader build error

HI, I am trying to build a secure bootloader using the instructions mentioned on ardupilot github ardupilot/Tools/scripts/signing at master · ArduPilot/ardupilot · GitHub.
But build is getting failed. I am not able to figure out the reason. I have attached the error details. Please help me out in figuring the reason.

pi@Amit:~/ardupilot $ Tools/scripts/build_bootloaders.py fmuv3 --signing-key=AMIT_public_key.dat
Building for fmuv3
Building secure bootloader
Running (./waf configure --board fmuv3 --bootloader --no-submodule-update --Werror --signed-fw)
Setting top to : /home/pi/ardupilot
Setting out to : /home/pi/ardupilot/build
Autoconfiguration : enabled
Setting board to : fmuv3
Using toolchain : arm-none-eabi
Checking for ‘g++’ (C++ compiler) : /usr/bin/arm-none-eabi-g++
Checking for ‘gcc’ (C compiler) : /usr/bin/arm-none-eabi-gcc
Checking for c flags ‘-MMD’ : yes
Checking for cxx flags ‘-MMD’ : yes
CXX Compiler : g++ 7.3.1
Checking for program ‘make’ : /usr/bin/make
Checking for program ‘arm-none-eabi-objcopy’ : /usr/bin/arm-none-eabi-objcopy
–bootloader
–bootloader --signed-fw
Setup for MCU STM32F427xx
Writing hwdef setup in /home/pi/ardupilot/build/fmuv3/hwdef.h
Writing DMA map
Generating ldscript.ld
Checking for env.py
env set APJ_BOARD_TYPE=STM32F427xx
env set USBID=0x1209/0x5741
env set EXT_FLASH_RESERVE_START_KB=0
env set DISABLE_SCRIPTING=True
env set BOOTLOADER_EMBED=1
env set ENABLE_DFU_BOOT=0
env set MAIN_STACK=0x600
env set BOARD_FLASH_SIZE=2048
env set APJ_BOARD_ID=9
env set CORTEX=cortex-m4
env set CHIBIOS_BUILD_FLAGS=USE_FATFS=no MCU=cortex-m4 CHIBIOS_PLATFORM_MK=os/hal/ports/STM32/STM32F4xx/platform.mk CHIBIOS_STARTUP_MK=os/common/startup/ARMCMx/compilers/GCC/mk/startup_stm32f4xx.mk
env set CPU_FLAGS=[‘-mcpu=cortex-m4’, ‘-mfpu=fpv4-sp-d16’, ‘-mfloat-abi=hard’]
env set PROCESS_STACK=0x1C00
env set EXT_FLASH_SIZE_MB=0
env set HAS_EXTERNAL_FLASH_SECTIONS=0
env set FLASH_TOTAL=16384
env set ENABLE_CRASHDUMP=0
env set IOMCU_FW=0
env set APP_RAM_START=None
env set FLASH_RESERVE_START_KB=0
env set PERIPH_FW=0
Enabling ChibiOS asserts : no
Disabling Watchdog : no
Enabling malloc guard : no
Enabling ChibiOS thread statistics : no
Enabling -Werror : yes
Checking for intelhex module: : disabled
Enabled OpenDroneID : no
Enabled firmware ID checking : yes
GPS Debug Logging : no
Enabled custom controller : no
Checking for HAVE_CMATH_ISFINITE : yes
Checking for HAVE_CMATH_ISINF : yes
Checking for HAVE_CMATH_ISNAN : yes
Checking for NEED_CMATH_ISFINITE_STD_NAMESPACE : yes
Checking for NEED_CMATH_ISINF_STD_NAMESPACE : yes
Checking for NEED_CMATH_ISNAN_STD_NAMESPACE : yes
Checking for header endian.h : not found
Checking for header byteswap.h : not found
Checking for HAVE_MEMRCHR : no
Configured VSCode Intellisense: : no
Checking for program ‘python’ : /usr/bin/python
Checking for python version >= 2.7.0 : 2.7.16
Checking for program ‘python’ : /usr/bin/python
Checking for python version >= 2.7.0 : 2.7.16
Source is git repository : yes
Update submodules : no
Checking for program ‘git’ : /usr/bin/git
Gtest : STM32 boards currently don’t support compiling gtest
Checking for program ‘arm-none-eabi-size’ : /usr/bin/arm-none-eabi-size
Benchmarks : disabled
Unit tests : disabled
Scripting : disabled
Scripting runtime checks : enabled
Debug build : disabled
Coverage build : disabled
SITL 32-bit build : disabled
Checking for program ‘rsync’ : /usr/bin/rsync
‘configure’ finished successfully (2.625s)
Running (./waf clean)
‘clean’ finished successfully (3.212s)
Running (./waf bootloader)
Waf: Entering directory `/home/pi/ardupilot/build/fmuv3’
Checking for env.py
No env.py found
Generating hwdef.h
–bootloader
–bootloader --signed-fw
Setup for MCU STM32F427xx
Writing hwdef setup in /home/pi/ardupilot/build/fmuv3/hwdef.h
Writing DMA map
Generating ldscript.ld
Embedding file bootloader.bin:/home/pi/ardupilot/Tools/bootloaders/fmuv3_bl.bin
Embedding file hwdef.dat:/home/pi/ardupilot/build/fmuv3/hw.dat
[1/7] Creating build/fmuv3/hwdef.h
[2/7] Creating build/fmuv3/modules/ChibiOS/include_dirs
[3/7] Compiling libraries/AP_Scripting/generator/src/main.c
[4/7] Creating build/fmuv3/ap_version.h
[5/7] Running python3 ${SRCROOT}/modules/DroneCAN/libcanard/dsdl_compiler/libcanard_dsdlc --header_only --outdir ${BUILDROOT}/modules/DroneCAN/libcanard/dsdlc_generated ${SRCROOT}/modules/DroneCAN/DSDL/uavcan ${SRCROOT}/modules/DroneCAN/DSDL/ardupilot ${SRCROOT}/modules/DroneCAN/DSDL/com ${SRCROOT}/modules/DroneCAN/DSDL/dronecan
Setup for MCU STM32F427xx
Writing hwdef setup in /home/pi/ardupilot/build/fmuv3/hwdef.h
Writing DMA map
No change in hwdef.h
Generating ldscript.ld

[6/7] Linking build/fmuv3/modules/ChibiOS/libch.a
[7/7] Processing /home/pi/ardupilot/build/fmuv3/libraries/AP_Scripting/lua_generated_bindings.cpp,/home/pi/ardupilot/build/fmuv3/libraries/AP_Scripting/lua_generated_bindings.h: libraries/AP_Scripting/generator/description/bindings.desc build/fmuv3/gen-bindings → build/fmuv3/libraries/AP_Scripting/lua_generated_bindings.cpp build/fmuv3/libraries/AP_Scripting/lua_generated_bindings.h
[1/104] ChibiOS: Compiling crt0_v7m.S
[2/104] ChibiOS: Compiling vectors.S
[3/104] ChibiOS: Compiling chcoreasm_v7m.S
[4/104] ChibiOS: Compiling chcore.c
[5/104] ChibiOS: Compiling chcore_v7m.c
[6/104] ChibiOS: Compiling crt1.c
[7/104] ChibiOS: Compiling chprintf.c
[8/104] ChibiOS: Compiling memstreams.c
[9/104] ChibiOS: Compiling nullstreams.c
[10/104] ChibiOS: Compiling osal.c
[11/104] ChibiOS: Compiling hal_adc_lld.c
[12/104] ChibiOS: Compiling hal_can_lld.c
[13/104] ChibiOS: Compiling hal_crypto_lld.c
[14/104] ChibiOS: Compiling hal_dac_lld.c
[15/104] ChibiOS: Compiling stm32_dma.c
[16/104] ChibiOS: Compiling stm32_exti.c
[17/104] ChibiOS: Compiling hal_pal_lld.c
[18/104] ChibiOS: Compiling hal_i2c_lld.c
[19/104] ChibiOS: Compiling hal_mac_lld.c
[20/104] ChibiOS: Compiling hal_usb_lld.c
[21/104] ChibiOS: Compiling hal_wspi_lld.c
[22/104] ChibiOS: Compiling hal_rtc_lld.c
[23/104] ChibiOS: Compiling hal_sdc_lld.c
[24/104] ChibiOS: Compiling hal_i2s_lld.c
[25/104] ChibiOS: Compiling hal_spi_lld.c
[26/104] ChibiOS: Compiling hal_eicu_lld.c
[27/104] ChibiOS: Compiling hal_gpt_lld.c
[28/104] ChibiOS: Compiling hal_icu_lld.c
[29/104] ChibiOS: Compiling hal_pwm_lld.c
[30/104] ChibiOS: Compiling hal_st_lld.c
[31/104] ChibiOS: Compiling hal_serial_lld.c
[32/104] ChibiOS: Compiling hal_uart_lld.c
[33/104] ChibiOS: Compiling hal_wdg_lld.c
[34/104] ChibiOS: Compiling hal_efl_lld.c
[35/104] ChibiOS: Compiling hal_lld.c
[36/104] ChibiOS: Compiling stm32_isr.c
[37/104] ChibiOS: Compiling nvic.c
[38/104] ChibiOS: Compiling hal.c
[39/104] ChibiOS: Compiling hal_adc.c
[40/104] ChibiOS: Compiling hal_buffers.c
[41/104] ChibiOS: Compiling hal_can.c
[42/104] ChibiOS: Compiling hal_crypto.c
[43/104] ChibiOS: Compiling hal_dac.c
[44/104] ChibiOS: Compiling hal_efl.c
[45/104] ChibiOS: Compiling hal_eicu.c
[46/104] ChibiOS: Compiling hal_flash.c
[47/104] ChibiOS: Compiling hal_gpt.c
[48/104] ChibiOS: Compiling hal_i2c.c
[49/104] ChibiOS: Compiling hal_i2s.c
[50/104] ChibiOS: Compiling hal_icu.c
[51/104] ChibiOS: Compiling hal_mac.c
[52/104] ChibiOS: Compiling hal_mmc_spi.c
[53/104] ChibiOS: Compiling hal_mmcsd.c
[54/104] ChibiOS: Compiling hal_pal.c
[55/104] ChibiOS: Compiling hal_pwm.c
[56/104] ChibiOS: Compiling hal_queues.c
[57/104] ChibiOS: Compiling hal_rtc.c
[58/104] ChibiOS: Compiling hal_sdc.c
[59/104] ChibiOS: Compiling hal_serial.c
[60/104] ChibiOS: Compiling hal_serial_usb.c
[61/104] ChibiOS: Compiling hal_sio.c
[62/104] ChibiOS: Compiling hal_spi.c
[63/104] ChibiOS: Compiling hal_st.c
[64/104] ChibiOS: Compiling hal_trng.c
[65/104] ChibiOS: Compiling hal_uart.c
[66/104] ChibiOS: Compiling hal_usb.c
[67/104] ChibiOS: Compiling hal_wdg.c
[68/104] ChibiOS: Compiling hal_wspi.c
[69/104] ChibiOS: Compiling chdelegates.c
[70/104] ChibiOS: Compiling chfactory.c
[71/104] ChibiOS: Compiling chmboxes.c
[72/104] ChibiOS: Compiling chmemcore.c
[73/104] ChibiOS: Compiling chmemheaps.c
[74/104] ChibiOS: Compiling chmempools.c
[75/104] ChibiOS: Compiling chobjcaches.c
[76/104] ChibiOS: Compiling chpipes.c
[77/104] ChibiOS: Compiling chcond.c
[78/104] ChibiOS: Compiling chdebug.c
[79/104] ChibiOS: Compiling chdynamic.c
[80/104] ChibiOS: Compiling chevents.c
[81/104] ChibiOS: Compiling chmsg.c
[82/104] ChibiOS: Compiling chmtx.c
[83/104] ChibiOS: Compiling chregistry.c
[84/104] ChibiOS: Compiling chschd.c
[85/104] ChibiOS: Compiling chsem.c
[86/104] ChibiOS: Compiling chstats.c
[87/104] ChibiOS: Compiling chsys.c
[88/104] ChibiOS: Compiling chthreads.c
[89/104] ChibiOS: Compiling chtm.c
[90/104] ChibiOS: Compiling chtrace.c
[91/104] ChibiOS: Compiling chvt.c
[92/104] ChibiOS: Compiling stubs.c
[93/104] ChibiOS: Compiling board.c
[94/104] ChibiOS: Compiling usbcfg.c
[95/104] ChibiOS: Compiling usbcfg_dualcdc.c
[96/104] ChibiOS: Compiling usbcfg_common.c
[97/104] ChibiOS: Compiling flash.c
[98/104] ChibiOS: Compiling malloc.c
[99/104] ChibiOS: Compiling hrt.c
[100/104] ChibiOS: Compiling stm32_util.c
[101/104] ChibiOS: Compiling bouncebuffer.c
[102/104] ChibiOS: Compiling watchdog.c
[103/104] ChibiOS: Compiling ch.cpp
[104/104] ChibiOS: Compiling syscalls_cpp.cpp

ChibiOS: Done!

arm-none-eabi-ar: creating modules/ChibiOS/libch.a

[ 8/99] Compiling libraries/AP_HAL_ChibiOS/CanIface.cpp
[ 9/99] Compiling libraries/AP_HAL_ChibiOS/CANFDIface.cpp
[10/99] Compiling libraries/AP_HAL_ChibiOS/AnalogIn.cpp
[11/99] Compiling libraries/AP_HAL_ChibiOS/stdio.cpp
[12/99] Compiling libraries/AP_HAL_ChibiOS/shared_dma.cpp
[13/99] Compiling libraries/AP_HAL_ChibiOS/sdcard.cpp
[14/99] Compiling libraries/AP_HAL_ChibiOS/UARTDriver.cpp
[15/99] Compiling libraries/AP_HAL_ChibiOS/Scheduler.cpp
[16/99] Compiling libraries/AP_HAL_ChibiOS/Device.cpp
[17/99] Compiling libraries/AP_HAL_ChibiOS/EventSource.cpp
[18/99] Compiling libraries/AP_HAL_ChibiOS/Semaphores.cpp
[19/99] Compiling libraries/AP_HAL_ChibiOS/I2CDevice.cpp
[20/99] Compiling libraries/AP_HAL_ChibiOS/QSPIDevice.cpp
[21/99] Compiling libraries/AP_HAL_ChibiOS/Util.cpp
[22/99] Compiling libraries/AP_HAL_ChibiOS/SoftSigReader.cpp
[23/99] Compiling libraries/AP_HAL_ChibiOS/RCInput.cpp
[24/99] Compiling libraries/AP_HAL_ChibiOS/DSP.cpp
[25/99] Compiling libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp
[26/99] Compiling libraries/AP_HAL_ChibiOS/SoftSigReaderInt.cpp
[27/99] Compiling libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp
[28/99] Compiling libraries/AP_HAL_ChibiOS/SPIDevice.cpp
[29/99] Compiling libraries/AP_HAL/utility/RCOutput_Tap_Linux.cpp
[30/99] Compiling libraries/AP_HAL/RCOutput.cpp
[31/99] Compiling libraries/AP_HAL/utility/BetterStream.cpp
[32/99] Compiling libraries/AP_HAL/utility/print_vprintf.cpp
[33/99] Compiling libraries/AP_HAL/DSP.cpp
[34/99] Compiling libraries/AP_HAL/utility/packetise.cpp
[35/99] Compiling libraries/AP_HAL/Storage.cpp
[36/99] Compiling libraries/AP_HAL/utility/getopt_cpp.cpp
[37/99] Compiling libraries/AP_HAL/utility/ftoa_engine.cpp
[38/99] Compiling libraries/AP_HAL/EventHandle.cpp
[39/99] Compiling libraries/AP_HAL/Semaphores.cpp
[40/99] Compiling libraries/AP_HAL/utility/replace.cpp
[41/99] Compiling libraries/AP_HAL/utility/Socket.cpp
[42/99] Compiling libraries/AP_HAL/Scheduler.cpp
[43/99] Compiling libraries/AP_HAL/utility/RingBuffer.cpp
[44/99] Compiling libraries/AP_HAL/Device.cpp
[45/99] Compiling libraries/AP_HAL/utility/RCOutput_Tap.cpp
[46/99] Compiling libraries/AP_HAL/utility/utoa_invert.cpp
[47/99] Compiling libraries/AP_HAL/utility/dsm.cpp
[48/99] Compiling libraries/AP_HAL/CANIface.cpp
[49/99] Compiling libraries/AP_HAL/utility/st24.cpp
[50/99] Compiling libraries/AP_HAL/HAL.cpp
[51/99] Compiling libraries/AP_HAL/Util.cpp
[52/99] Compiling libraries/AP_HAL/utility/srxl.cpp
[53/99] Compiling libraries/AP_HAL/system.cpp
[54/99] Compiling libraries/AP_HAL/GPIO.cpp
[55/99] Compiling libraries/AP_HAL/utility/sumd.cpp
[56/99] Compiling libraries/AP_HAL/SIMState.cpp
[57/99] Compiling libraries/AP_HAL_ChibiOS/Storage.cpp
[58/99] Compiling libraries/AP_HAL_ChibiOS/system.cpp
[59/99] Compiling libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp
[60/99] Compiling libraries/AP_HAL_ChibiOS/GPIO.cpp
[61/99] Compiling libraries/AP_HAL_ChibiOS/RCOutput.cpp
[62/99] Compiling libraries/AP_Math/location_double.cpp
[63/99] Compiling libraries/AP_Math/crc.cpp
[64/99] Compiling libraries/AP_Math/vector2.cpp
[65/99] Compiling libraries/AP_Math/polyfit.cpp
[66/99] Linking build/fmuv3/lib/libap.a
[67/99] Compiling libraries/AP_Math/SplineCurve.cpp
[68/99] Compiling libraries/AP_Math/polygon.cpp
[69/99] Compiling libraries/AP_Math/AP_Math.cpp
[70/99] Compiling libraries/AP_Math/location.cpp
[71/99] Compiling libraries/AP_Math/matrix3.cpp
[72/99] Compiling libraries/AP_Math/chirp.cpp
[73/99] Compiling libraries/AP_Math/spline5.cpp
[74/99] Compiling libraries/AP_Math/matrix_alg.cpp
[75/99] Compiling libraries/AP_Math/control.cpp
[76/99] Compiling libraries/AP_Math/AP_GeodesicGrid.cpp
[77/99] Compiling libraries/AP_Math/matrixN.cpp
[78/99] Compiling libraries/AP_CheckFirmware/AP_CheckFirmware_secure_command.cpp
[79/99] Compiling libraries/AP_CheckFirmware/AP_CheckFirmware.cpp
[80/99] Compiling libraries/AP_CheckFirmware/monocypher.cpp
[81/99] Compiling modules/DroneCAN/libcanard/canard.c
[82/99] Compiling libraries/AP_Math/SCurve.cpp
[83/99] Compiling libraries/AP_Math/quaternion.cpp
[84/99] Compiling libraries/AP_Math/vector3.cpp
[85/99] Linking build/fmuv3/Tools/AP_Bootloader/liblibcanard.a
[86/99] Compiling libraries/AP_HAL_ChibiOS/GPIO.cpp
[87/99] Compiling libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp
[88/99] Compiling libraries/AP_HAL_ChibiOS/RCOutput.cpp
[89/99] Compiling libraries/AP_HAL_ChibiOS/Storage.cpp
[90/99] Compiling libraries/AP_HAL_ChibiOS/system.cpp
[91/99] Compiling Tools/AP_Bootloader/AP_Bootloader.cpp
[92/99] Compiling Tools/AP_Bootloader/support.cpp
[93/99] Compiling Tools/AP_Bootloader/bl_protocol.cpp
[94/99] Compiling Tools/AP_Bootloader/can.cpp
[95/99] Linking build/fmuv3/lib/libAP_Bootloader_libs.a
[96/99] Linking build/fmuv3/bootloader/AP_Bootloader
/usr/lib/gcc/arm-none-eabi/7.3.1/…/…/…/arm-none-eabi/bin/ld:common.ld:202 cannot move location counter backwards (from 0000000008007b40 to 0000000008004000)
collect2: error: ld returned 1 exit status

Waf: Leaving directory `/home/pi/ardupilot/build/fmuv3’
Build failed
→ task in ‘bootloader/AP_Bootloader’ failed (exit status 1):
{task 548497720936: cxxprogram AP_Bootloader.cpp.2.o,bl_protocol.cpp.2.o,can.cpp.2.o,support.cpp.2.o,AnalogIn.cpp.0.o,CANFDIface.cpp.0.o,CanIface.cpp.0.o,DSP.cpp.0.o,Device.cpp.0.o,EventSource.cpp.0.o,I2CDevice.cpp.0.o,QSPIDevice.cpp.0.o,RCInput.cpp.0.o,RCOutput_bdshot.cpp.0.o,RCOutput_serial.cpp.0.o,SPIDevice.cpp.0.o,Scheduler.cpp.0.o,Semaphores.cpp.0.o,SoftSigReader.cpp.0.o,SoftSigReaderInt.cpp.0.o,UARTDriver.cpp.0.o,Util.cpp.0.o,sdcard.cpp.0.o,shared_dma.cpp.0.o,stdio.cpp.0.o → AP_Bootloader}
(run with -v to display more information)
Build failed: ./waf bootloader
Failed boards: [‘fmuv3’]

Can anyone help me out on this?

You are using fmuv3 or pixhawk 2.4.8 Secure boot is only supported on boards with at least 32k of flash space for the bootloader.
You can use secure boot on older other boards if you change the hwdef.dat and hwdef-bl.dat to add more space for the bootloader.

@ChristoGeorge You mean to keep the bootloader size below 16KB we need to change the hwdef.dat and hwdef-bl.dat, right?
I did try to comment few of the definitions in both the file but it did not help. Still the bootloader size is same.
is it somewhere else I need to change?
In my Scenario I am looking to use only 2 telemetry port, 1GPS port, I2C port, battery port.

What I have tried untill now I have explained that below…

I changed few of the parameters so that bootloader and firmware build successfully.

changed bootloader load size to 32KB

FLASH_BOOTLOADER_LOAD_KB 32 (in hwdef-bl.dat)

changed HAL storage size to 32768

define HAL_STORAGE_SIZE 32768 (in hwdef.dat)

changed default space to reserve for bootloader and storage at start of flash

flash_reserve_start = get_config(
    'FLASH_RESERVE_START_KB', default=32, type=int)  (in chibios_hwdef.py)

After this I followed the procedure as mentioned on the github for secure bootloader.
After building & signing bootloader, size comes around 28KB
Firmware build also happens successfully. Then

  • Accessing the boot0 pin of the flight controller, got the FC in boot mode and using STM32 Cube programmer uploaded the signed bootloader.
  • Next using QgroundControl I installed my signed firmware.(tried with mission planner but it was giving error as “lost communication with the board”).
  • Once installation happened it was booting succesfully and connecting to both mission planner and Qground. I also checked free memory in mission planner and it was around 30KB.
  • But with this procedure I am facing few issues as mentioned below.
    1. Only Once I am able to install the firmware. If I try to install firmware once again (either signed or unsigned ), installation fails in between and board does not boot again.
      To fix that again I have to access the bootloader to install bootloader & firmware and then install firmware. I am not sure what can fix this or I am doing some thing wrong.

@ChristoGeorge @amitraushan

Is it working? I have also tried this, but build error was there when i tried these steps.

@rmackay9 @siddharth @tridge
kindly guide

@AmitSingh For which board you are trying to build? Can you post your build error?

i was trying to build for fmuv3