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
The auto-label step in pull_request_target runs without a repo
checkout, so gh pr view/edit fail with 'not a git repository'.
Setting GH_REPO points gh at the right repo without needing a
checkout step.
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
Mavlink::request_stop() unconditionally called
_sign_control.write_key_and_timestamp() on every instance shutdown,
which created /fs/microsd/mavlink/mavlink-signing-key.bin filled with a
zero key and zero timestamp on FCs that never enabled signing.
The shutdown write is redundant: every signing state transition
(KEY_ACCEPTED, SIGNING_DISABLED) already persists synchronously inside
check_for_signing() before returning. The in-memory state is always
flushed to disk at the moment it changes.
Aggravated by mavlink_main.cpp:3334 calling request_stop() up to 1000
times in a tight loop while waiting for the thread to exit, plus the
~Mavlink() destructor path. Each call re-truncates and rewrites the
phantom file.
Reported by Jake Dahl on two separate flight controllers running
mainline.
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
The PR-time SBOM license check was using `submodules: false`, so when
generate_sbom.py ran the new submodule directory was empty. The script
treats uninitialized submodules as `(not checked out) -> NOASSERTION
(skipped)` rather than a failure, which let PR #27184 (adding
PX4-OpticalFlow as a submodule) pass without ever inspecting the actual
repo for a LICENSE file. The monthly audit then caught it (#27217)
because it uses `submodules: recursive`.
Switch the PR-time job to `submodules: recursive` so license issues
are caught at PR time rather than on the next monthly audit. The job
only runs when .gitmodules, license-overrides.yaml, or
generate_sbom.py change, so the extra clone cost is bounded.
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
Bumps the submodule pointer to pick up the BSD-3-Clause LICENSE file
added in PX4/PX4-OpticalFlow#20.
Resolves the SBOM audit NOASSERTION finding without needing a manual
override entry in Tools/ci/license-overrides.yaml.
Fixes#27217
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
Remove ASPD_SCALE_NSD, ASPD_BETA_NOISE, ASPD_TAS_GATE, ASPD_BETA_GATE as these
are never changed in practice. Keep ASPD_WIND_NSD and ASPD_TAS_NOISE tunable as
they are relevant for high-altitude (wind NSD) and high-speed (TAS noise) use cases.
* feat: add driver for ADS7128 ADC
* style: used make format
* fix: only read 1 byte in adc_get()
* fix: set correct min/max/def value for VRef
* fix: print i2c address in status
* feat: add threshhold to failures before reset
* feat: add failure_threshhold_count
* style: remove unused variable definition from module.yaml
* fix: removed retry logic from poll functions
* fix: decreased sleep time in probe function
* feat: add driver for ADS7128 ADC
* style: used make format
* fix: only read 1 byte in adc_get()
* fix: changed scheduling logic
* fix: ensure no false values are published
* fix: removed unused variable definition
* style: used make format
* fix: removed merge artifact
* fix: removed some merge artifacts
Integrators can declare read-only parameters in a per-board YAML file:
readonly_params.yaml.
There are two ways to define the read-only params:
- "block": default writable, explicitly list params to be locked
- "allow": default readonly, explicitly list params to be writable
Enforcement is activated by `param lock` in rcS after all startup
scripts have run, so board defaults and airframe scripts can still set
params during init.
The feedback via MAVLink uses the new
MAV_PARAM_ERROR_READ_ONLY as part of the PARAM_ERROR message.