The bootloader boot-delay feature has been mechanically broken on
every modern FMU board since the STM32F7/H7 transition. It has three
independent bugs that prevent it from ever working:
1. Offset mismatch: BOOT_DELAY_ADDRESS is hardcoded to 0x1a0, but the
NuttX vector table is 504 B (F76x) to 664 B (H743) long. The
linker places _bootdelay_signature at ALIGN(32) past end of
vectors (e.g. 0x2a0 on CubeOrange), never at 0x1a0. The bootloader
reads random exception_common pointers in place of the magic and
never matches BOOT_DELAY_SIGNATURE1/2. Verified on CubeOrange with
objdump of cubepilot_cubeorange_default.elf.
2. Flash cache never flushes: fc_write() stores arbitrary writes in
cache line 1 and only flushes on a very specific condition tied
to the sequential firmware upload flow. A standalone write during
PROTO_SET_DELAY is cached forever. fc_read() then returns the
cached value, so the post-write verify lies and the bootloader
reports success. Nothing ever reaches flash.
3. H7 write granularity: the STM32H7 flash controller requires a
full 32-byte program cycle per write. Single 32-bit writes from
flash_func_write_word() would not be accepted by the controller
even if they reached it.
The feature has been silently dead on every H7/F7 FMU board for
years and no one noticed, which is strong evidence nothing actually
depends on it. Rather than fix it (which would mean rewriting
PROTO_SET_DELAY, the flash cache path, and the H7 flash programming
path), remove it.
Changes:
- bl.c: PROTO_SET_DELAY case now immediately NACKs (goto cmd_bad)
so clients that still send the command get a clear rejection
instead of the previous silent fake-success. The opcode stays in
the protocol enum for backwards compatibility.
- bl.h: drop BOOT_DELAY_SIGNATURE1/2 and BOOT_DELAY_MAX.
- stm/stm32_common/main.c, nxp/imxrt_common/main.c: drop the
startup boot-delay sig check block.
- image_toc.c: decouple find_toc() from BOOT_DELAY_ADDRESS.
BOARD_IMAGE_TOC_OFFSET is now the required define when
BOOTLOADER_USE_TOC is enabled. The body is wrapped in #ifdef
BOOTLOADER_USE_TOC and falls back to a stub returning false when
the TOC is not in use (no upstream board currently enables it).
- Linker scripts: strip EXTERN(_bootdelay_signature) and the
FILL/. += 8 block from all 142 affected .ld files across boards/.
- hw_config.h: strip the #define BOOT_DELAY_ADDRESS and its comment
block entry from all 48 affected boards.
- Tools/px4_uploader.py, Tools/teensy_uploader.py: remove --boot-delay,
set_boot_delay(), and SET_BOOT_DELAY client-side counterpart.
Smoke-built on cubepilot_cubeorange_default and
cubepilot_cubeorange_bootloader; no link errors, no unresolved
symbols, flash usage unchanged.
Tested:
- New BL, new FW
- Old BL, old FW
- Old BL, new FW
- New BL, old FW
- split up old module into two, one handling setpoint generation, one control
- add lateral and longitudinal control setpoints topics that can also be
injected from companion computer
- add configuration topics that (optionally) configure the controller
with limits and momentary settings
Signed-off-by: RomanBapst <bapstroman@gmail.com>
* usb: Added parameter to enable always starting mavlink on USB.
Refactored cdcacm_init into a module and added a paramter to allow always starting mavlink on
USB, also added a paramter to choose the mode. The current default behavior is to wait and listen
for data on USB and auto-detect the protocol (mavlink, nsh, ublox). This results in the mavlink
stream not starting until something else on the mavlink network sends a packet first. The new
default behavior is to always start mavlink.
Added parameters
MAV_USB_ENABLE -- default 1 (always start mavlink on USB)
MAV_USE_MODE -- default 3 (onboard)
* added 3 retries for opening serial port in mavlink, removed sleep before sercon
* added DRIVERS_CDCACM_AUTOSTART to ark-v6x default.px4board
* added CONFIG_DRIVERS_CDCACM_AUTOSTART=y to default.px4board for boards with CONFIG_CDCACM in their nsh/defconfig
* format
* remove PGA460 from COMMON_DISTANCE_SENSOR to save flash
* remove LIS2MDL from COMMON_MAGNETOMETER to save flash
* disable CONFIG_DRIVERS_CDCACM_AUTOSTART for fmu-v5 protected.px4board
* moved and renamed parameters, removed mode logic in mavlink
* changed parameter names, added mode none
* remove parameters from mavlink
IMUs were replaced in V3 with 2x ICM42688P. This configuration should
work with all revisions of Matek F743 Slim board, including V1, V1.5
and interim variant of V3 (ICM42688P + ICM42605).
Signed-off-by: Andrei Korigodskii <akorigod@gmail.com>
- during casual testing on default configs the stack was penetration was reaching ~90% which is a bit too close for comfort
- increasing by 50% to be conservative
* Fixedwing rate control into a separate module
* Start fw_rate_control for vtol
* Move over airspeed related parameters to fw_rate_control
Co-authored-by: Silvan Fuhrer <silvan@auterion.com>
- update all msgs to be directly compatible with ROS2
- microdds_client improvements
- timesync
- reduced code size
- add to most default builds if we can afford it
- lots of other little changes
- purge fastrtps (I tried to save this multiple times, but kept hitting roadblocks)