feat(params): add board-level read-only parameter support (#26522)

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.
This commit is contained in:
Julian Oes
2026-04-27 09:06:43 +12:00
committed by GitHub
parent efd05431e8
commit b48ec2dd68
16 changed files with 276 additions and 9 deletions
+4
View File
@@ -699,6 +699,10 @@ else
. ${R}etc/init.d/rc.autostart.post
fi
#
# Lock read-only parameters (if configured for this board).
#
param lock
set BOARD_BOOTLOADER_UPGRADE ${R}etc/init.d/rc.board_bootloader_upgrade
if [ -f $BOARD_BOOTLOADER_UPGRADE ]