Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions ROMFS/px4fmu_common/init.d/rcS
Original file line number Diff line number Diff line change
Expand Up @@ -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 ]
Expand Down
56 changes: 56 additions & 0 deletions docs/en/advanced/parameters_and_configurations.md
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
16 changes: 16 additions & 0 deletions src/lib/parameters/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,16 @@ add_custom_command(OUTPUT ${generated_serial_params_file} ${generated_module_par
COMMENT "Generating serial_params.c"
)

# readonly params config (used by both px_process_params.py and px_generate_params.py)
set(READONLY_PARAMS_CONFIG "${PX4_BOARD_DIR}/readonly_params.yaml")
if(EXISTS ${READONLY_PARAMS_CONFIG})
set(READONLY_PARAMS_ARG "--readonly-config" "${READONLY_PARAMS_CONFIG}")
set(READONLY_PARAMS_DEPEND "${READONLY_PARAMS_CONFIG}")
else()
set(READONLY_PARAMS_ARG "")
set(READONLY_PARAMS_DEPEND "")
endif()

set(parameters_xml ${PX4_BINARY_DIR}/parameters.xml)
set(parameters_json ${PX4_BINARY_DIR}/parameters.json)
add_custom_command(OUTPUT ${parameters_xml} ${parameters_json} ${parameters_json}.xz
Expand All @@ -108,6 +118,7 @@ add_custom_command(OUTPUT ${parameters_xml} ${parameters_json} ${parameters_json
--compress
--overrides ${PARAM_DEFAULT_OVERRIDES}
--board ${PX4_BOARD}
${READONLY_PARAMS_ARG}
#--verbose
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/validate_json.py
--schema-file ${PX4_SOURCE_DIR}/src/modules/mavlink/mavlink/component_information/parameter.schema.json
Expand All @@ -117,21 +128,26 @@ add_custom_command(OUTPUT ${parameters_xml} ${parameters_json} ${parameters_json
DEPENDS
${generated_serial_params_file}
${generated_module_params_file}
${READONLY_PARAMS_DEPEND}
px4params/srcparser.py
px4params/srcscanner.py
px4params/jsonout.py
px4params/xmlout.py
px4params/readonly_config.py
px_process_params.py
COMMENT "Generating parameters.xml"
)
add_custom_target(parameters_xml DEPENDS ${parameters_xml})

# generate px4_parameters.hpp

add_custom_command(OUTPUT px4_parameters.hpp
COMMAND ${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/px_generate_params.py
--xml ${parameters_xml} --dest ${CMAKE_CURRENT_BINARY_DIR}
${READONLY_PARAMS_ARG}
DEPENDS
${PX4_BINARY_DIR}/parameters.xml
${READONLY_PARAMS_DEPEND}
px_generate_params.py
templates/px4_parameters.hpp.jinja
)
Expand Down
17 changes: 17 additions & 0 deletions src/lib/parameters/param.h
Original file line number Diff line number Diff line change
Expand Up @@ -175,6 +175,23 @@ __EXPORT const char *param_name(param_t param);
*/
__EXPORT bool param_is_volatile(param_t param);

/**
* Obtain the read-only state of a parameter.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @return true if the parameter is read-only
*/
__EXPORT bool param_is_readonly(param_t param);

/**
* Lock all read-only parameters.
*
* Before this call, read-only parameters can be freely modified (e.g. by
* startup scripts). After this call, any attempt to set, set-default, or
* reset a read-only parameter will be rejected.
*/
__EXPORT void param_lock_readonly(void);

/**
* Test whether a parameter's value has changed from the default.
*
Expand Down
14 changes: 14 additions & 0 deletions src/lib/parameters/parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -413,6 +413,11 @@ param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_
return PX4_ERROR;
}

if (param_is_readonly(param)) {
PX4_WARN("param %s is read-only", param_name(param));
return PX4_ERROR;
}

int result = -1;
bool param_changed = false;
perf_begin(param_set_perf);
Expand Down Expand Up @@ -544,6 +549,11 @@ int param_set_default_value(param_t param, const void *val)
return PX4_ERROR;
}

if (param_is_readonly(param)) {
PX4_WARN("param %s is read-only", param_name(param));
return PX4_ERROR;
}

int result = PX4_ERROR;


Expand Down Expand Up @@ -615,6 +625,10 @@ static int param_reset_internal(param_t param, bool notify = true, bool autosave
return false;
#endif

if (param_is_readonly(param)) {
return 0; // silently skip — param_reset_all loops over all params
}

bool param_found = user_config.contains(param);

if (handle_in_range(param)) {
Expand Down
20 changes: 20 additions & 0 deletions src/lib/parameters/parameters_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,26 @@ bool param_is_volatile(param_t param)
return false;
}

static bool params_locked = false;

bool param_is_readonly(param_t param)
{
if (params_locked && handle_in_range(param)) {
for (const auto &p : px4::parameters_readonly) {
if (static_cast<px4::params>(param) == p) {
return true;
}
}
}

return false;
}

void param_lock_readonly()
{
params_locked = true;
}

size_t param_size(param_t param)
{
if (handle_in_range(param)) {
Expand Down
2 changes: 2 additions & 0 deletions src/lib/parameters/px4params/jsonout.py
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,8 @@ def get_typed_value(value: str, type_name: str):

if param.GetVolatile():
curr_param['volatile'] = True
if param.GetReadonly():
curr_param['readOnly'] = True

last_param_name = param.GetName()
for code in param.GetFieldCodes():
Expand Down
3 changes: 2 additions & 1 deletion src/lib/parameters/px4params/markdownout.py
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,8 @@ def __init__(self, groups):
if bitmask_list:
result += bitmask_output
# Format the ranges as a table.
result += f"Reboot | minValue | maxValue | increment | default | unit\n--- | --- | --- | --- | --- | ---\n{'&check;' if reboot_required else '&nbsp;' } | {min_val} | {max_val} | {increment} | {def_val} | {unit} | \n\n"
is_readonly = param.GetReadonly()
result += f"Reboot | minValue | maxValue | increment | default | unit | Read-Only\n--- | --- | --- | --- | --- | --- | ---\n{'&check;' if reboot_required else '&nbsp;' } | {min_val} | {max_val} | {increment} | {def_val} | {unit} | {'&check;' if is_readonly else '&nbsp;'}\n\n"

self.output = result

Expand Down
48 changes: 48 additions & 0 deletions src/lib/parameters/px4params/readonly_config.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
"""
Shared helper to load readonly parameter configuration from YAML.
"""
import sys

try:
import yaml
except ImportError as e:
print("Failed to import yaml: " + str(e))
print("")
print("You may need to install it using:")
print(" pip3 install --user pyyaml")
print("")
sys.exit(1)


def load_readonly_params(readonly_config, all_param_names):
"""
Load readonly parameter config and return the set of readonly param names.

@param readonly_config: path to readonly_params.yaml
@param all_param_names: set of all known parameter names
@return: set of readonly parameter names
"""
if readonly_config is None:
return set()

with open(readonly_config, 'r') as f:
config = yaml.safe_load(f)

mode = config.get('mode', 'block')
listed_params = set(config.get('parameters', []))

# Validate that all listed parameters actually exist
unknown = listed_params - all_param_names
if unknown:
print("Error: readonly_params.yaml lists unknown parameters: %s" % ', '.join(sorted(unknown)))
sys.exit(1)

if mode == 'block':
# Listed params are read-only
return listed_params
elif mode == 'allow':
# Only listed params are writable, all others are read-only
return all_param_names - listed_params
else:
print("Error: readonly_params.yaml has unknown mode '%s' (expected 'block' or 'allow')" % mode)
sys.exit(1)
10 changes: 10 additions & 0 deletions src/lib/parameters/px4params/srcparser.py
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,7 @@ def __init__(self, name, type, default = ""):
self.category = ""
self.volatile = False
self.boolean = False
self.readonly = False

def GetName(self):
return self.name
Expand All @@ -80,6 +81,9 @@ def GetVolatile(self):
def GetBoolean(self):
return self.boolean

def GetReadonly(self):
return self.readonly

def SetField(self, code, value):
"""
Set named field value
Expand Down Expand Up @@ -110,6 +114,12 @@ def SetBoolean(self):
"""
self.boolean = True

def SetReadonly(self):
"""
Set readonly flag
"""
self.readonly = True

def SetCategory(self, category):
"""
Set param category
Expand Down
2 changes: 2 additions & 0 deletions src/lib/parameters/px4params/xmlout.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,8 @@ def __init__(self, groups, board):
xml_param.attrib["volatile"] = "true"
if param.GetBoolean():
xml_param.attrib["boolean"] = "true"
if param.GetReadonly():
xml_param.attrib["readonly"] = "true"
if (param.GetCategory()):
xml_param.attrib["category"] = param.GetCategory()
last_param_name = param.GetName()
Expand Down
12 changes: 9 additions & 3 deletions src/lib/parameters/px_generate_params.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,13 +18,15 @@
sys.exit(1)

import os
from px4params.readonly_config import load_readonly_params

def generate(xml_file, dest='.'):
def generate(xml_file, dest='.', readonly_config=None):
"""
Generate px4 param source from xml.

@param xml_file: input parameter xml file
@param dest: Destination directory for generated files
@param readonly_config: path to readonly_params.yaml (optional)
None means to scan everything.
"""
# pylint: disable=broad-except
Expand All @@ -39,6 +41,9 @@ def generate(xml_file, dest='.'):

params = sorted(params, key=lambda name: name.attrib["name"])

all_param_names = set(p.attrib["name"] for p in params)
readonly_params = load_readonly_params(readonly_config, all_param_names)

script_path = os.path.dirname(os.path.realpath(__file__))

# for jinja docs see: http://jinja.pocoo.org/docs/2.9/api/
Expand All @@ -55,13 +60,14 @@ def generate(xml_file, dest='.'):
template = env.get_template(template_file)
with open(os.path.join(
dest, template_file.replace('.jinja','')), 'w') as fid:
fid.write(template.render(params=params))
fid.write(template.render(params=params, readonly_params=readonly_params))

if __name__ == "__main__":
arg_parser = argparse.ArgumentParser()
arg_parser.add_argument("--xml", help="parameter xml file")
arg_parser.add_argument("--dest", help="destination path", default=os.path.curdir)
arg_parser.add_argument("--readonly-config", help="path to readonly_params.yaml", default=None)
args = arg_parser.parse_args()
generate(xml_file=args.xml, dest=args.dest)
generate(xml_file=args.xml, dest=args.dest, readonly_config=args.readonly_config)

# vim: set et fenc=utf-8 ff=unix sts=4 sw=4 ts=4 :
Loading
Loading