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
@@ -358,6 +358,62 @@ This ensures that metadata is always up-to-date with the code running on the veh
This process is the same as for [events metadata](../concept/events_interface.md#publishing-event-metadata-to-a-gcs).
For more information see [PX4 Metadata (Translation & Publication)](../advanced/px4_metadata.md)
## Read-Only Parameters
Integrators who productize PX4 can lock down parameters so that end users cannot change safety-critical or product-defining settings.
This works in two phases:
1. **Build time** — a YAML file in the board directory declares _which_ parameters are read-only.
2. **Run time**`param lock` in the startup script activates enforcement.
Before the lock, all parameters (including those on the read-only list) can be freely set by startup scripts (`rc.board_defaults`, airframe scripts, `config.txt`, etc.).
After the lock, any attempt to modify a read-only parameter is rejected.
### Configuration
Create `boards/<vendor>/<board>/readonly_params.yaml` with the following format:
```yaml
# mode: 'block' = listed params are read-only (all others writable)
# mode: 'allow' = only listed params are writable (all others read-only)
mode: block
parameters:
- SYS_AUTOSTART
- SYS_AUTOCONFIG
- BAT1_N_CELLS
```
The two modes are:
- **`block`**: The listed parameters are read-only; all other parameters remain writable.
- **`allow`**: Only the listed parameters are writable; all others become read-only.
All parameter names in the list are validated at build time — the build will fail if any listed parameter does not exist in the firmware.
Boards without this file have no read-only enforcement (fully backward compatible).
### Locking
The `param lock` command is called in `rcS` after all startup scripts have finished setting parameters.
Before this call, startup scripts can freely use `param set-default` and `param set` on any parameter, including those on the read-only list.
After `param lock`, the read-only list is enforced.
To set a specific locked value, use `param set-default` in a board startup script (e.g. `rc.board_defaults`) to set the desired default _before_ the lock activates.
### Enforcement (after lock)
Read-only parameters are enforced at all entry points:
- **`param set`** and **`param set-default`** shell commands return an error.
- **MAVLink PARAM_SET** returns a `MAV_PARAM_ERROR_READ_ONLY` error to the GCS.
- **`param_set()`**, **`param_set_default_value()`** C API calls return `PX4_ERROR`.
- **`param reset`** silently skips read-only parameters (since `param_reset_all` loops over all params).
- **`param import`** / **`param load`** from file silently skips read-only parameters.
### Notes
- The read-only list is compiled into firmware as a `constexpr` array, so there is zero runtime overhead when the list is empty.
- If no `readonly_params.yaml` file exists for a board, `param lock` is a no-op.
## Further Information
- [Finding/Updating Parameters](../advanced_config/parameters.md)