mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-09 22:08:56 +08:00
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:
@@ -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 ]
|
||||
|
||||
@@ -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)
|
||||
|
||||
@@ -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
|
||||
@@ -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
|
||||
@@ -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
|
||||
)
|
||||
|
||||
@@ -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.
|
||||
*
|
||||
|
||||
@@ -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);
|
||||
@@ -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;
|
||||
|
||||
|
||||
@@ -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)) {
|
||||
|
||||
@@ -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)) {
|
||||
|
||||
@@ -82,6 +82,8 @@ class JsonOutput():
|
||||
|
||||
if param.GetVolatile():
|
||||
curr_param['volatile'] = True
|
||||
if param.GetReadonly():
|
||||
curr_param['readOnly'] = True
|
||||
|
||||
last_param_name = param.GetName()
|
||||
for code in param.GetFieldCodes():
|
||||
|
||||
@@ -104,7 +104,8 @@ If a listed parameter is missing from the Firmware see: [Finding/Updating Parame
|
||||
if bitmask_list:
|
||||
result += bitmask_output
|
||||
# Format the ranges as a table.
|
||||
result += f"Reboot | minValue | maxValue | increment | default | unit\n--- | --- | --- | --- | --- | ---\n{'✓' if reboot_required else ' ' } | {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{'✓' if reboot_required else ' ' } | {min_val} | {max_val} | {increment} | {def_val} | {unit} | {'✓' if is_readonly else ' '}\n\n"
|
||||
|
||||
self.output = result
|
||||
|
||||
|
||||
@@ -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)
|
||||
@@ -61,6 +61,7 @@ class Parameter(object):
|
||||
self.category = ""
|
||||
self.volatile = False
|
||||
self.boolean = False
|
||||
self.readonly = False
|
||||
|
||||
def GetName(self):
|
||||
return self.name
|
||||
@@ -80,6 +81,9 @@ class Parameter(object):
|
||||
def GetBoolean(self):
|
||||
return self.boolean
|
||||
|
||||
def GetReadonly(self):
|
||||
return self.readonly
|
||||
|
||||
def SetField(self, code, value):
|
||||
"""
|
||||
Set named field value
|
||||
@@ -110,6 +114,12 @@ class Parameter(object):
|
||||
"""
|
||||
self.boolean = True
|
||||
|
||||
def SetReadonly(self):
|
||||
"""
|
||||
Set readonly flag
|
||||
"""
|
||||
self.readonly = True
|
||||
|
||||
def SetCategory(self, category):
|
||||
"""
|
||||
Set param category
|
||||
|
||||
@@ -43,6 +43,8 @@ class XMLOutput():
|
||||
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()
|
||||
|
||||
@@ -18,13 +18,15 @@ except ImportError as e:
|
||||
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
|
||||
@@ -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/
|
||||
@@ -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 :
|
||||
|
||||
@@ -47,7 +47,7 @@ from __future__ import print_function
|
||||
import sys
|
||||
import os
|
||||
import argparse
|
||||
from px4params import srcscanner, srcparser, injectxmlparams, xmlout, markdownout, jsonout
|
||||
from px4params import srcscanner, srcparser, injectxmlparams, xmlout, markdownout, jsonout, readonly_config
|
||||
|
||||
import lzma #to create .xz file
|
||||
import json
|
||||
@@ -102,6 +102,10 @@ def main():
|
||||
default="{}",
|
||||
metavar="OVERRIDES",
|
||||
help="a dict of overrides in the form of a json string")
|
||||
parser.add_argument("--readonly-config",
|
||||
default=None,
|
||||
metavar="FILENAME",
|
||||
help="path to readonly_params.yaml")
|
||||
|
||||
args = parser.parse_args()
|
||||
|
||||
@@ -143,6 +147,18 @@ def main():
|
||||
param.default = val
|
||||
print("OVERRIDING {:s} to {:s}!!!!!".format(name, val))
|
||||
|
||||
# Mark readonly parameters
|
||||
if args.readonly_config:
|
||||
all_param_names = set()
|
||||
for group in param_groups:
|
||||
for param in group.GetParams():
|
||||
all_param_names.add(param.GetName())
|
||||
readonly_params = readonly_config.load_readonly_params(args.readonly_config, all_param_names)
|
||||
for group in param_groups:
|
||||
for param in group.GetParams():
|
||||
if param.GetName() in readonly_params:
|
||||
param.SetReadonly()
|
||||
|
||||
output_files = []
|
||||
|
||||
# Output to XML file
|
||||
|
||||
@@ -47,5 +47,13 @@ static constexpr params parameters_volatile[] = {
|
||||
{% endfor %}
|
||||
};
|
||||
|
||||
static constexpr params parameters_readonly[] = {
|
||||
{% for param in params %}
|
||||
{%- if param.attrib["name"] in readonly_params %}
|
||||
params::{{ param.attrib["name"] }},
|
||||
{%- endif -%}
|
||||
{% endfor %}
|
||||
};
|
||||
|
||||
|
||||
} // namespace px4
|
||||
|
||||
@@ -226,6 +226,9 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
|
||||
PX4_ERR("param types mismatch param: %s", name);
|
||||
send_error(MAV_PARAM_ERROR_TYPE_MISMATCH, name, -1, msg->sysid, msg->compid);
|
||||
|
||||
} else if (param_is_readonly(param)) {
|
||||
PX4_WARN("param %s is read-only", name);
|
||||
send_error(MAV_PARAM_ERROR_READ_ONLY, name, -1, msg->sysid, msg->compid);
|
||||
|
||||
} else {
|
||||
// According to the mavlink spec we should always acknowledge a write operation.
|
||||
|
||||
@@ -81,6 +81,7 @@ static int do_import(const char *param_file_name = nullptr);
|
||||
static int do_show(const char *search_string, bool only_changed);
|
||||
static int do_show_for_airframe();
|
||||
static int do_show_all();
|
||||
static int do_show_locked();
|
||||
static int do_show_quiet(const char *param_name);
|
||||
static int do_show_index(const char *index, bool used_index);
|
||||
static void do_show_print(void *arg, param_t param);
|
||||
@@ -138,6 +139,7 @@ $ reboot
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("show", "Show parameter values");
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('a', "Show all parameters (not just used)", true);
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('c', "Show only changed params (unused too)", true);
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('l', "Show only locked (read-only) params", true);
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('q', "quiet mode, print only param value (name needs to be exact)", true);
|
||||
PRINT_MODULE_USAGE_ARG("<filter>", "Filter by param name (wildcard at end allowed, eg. sys_*)", true);
|
||||
|
||||
@@ -179,6 +181,8 @@ $ reboot
|
||||
PRINT_MODULE_USAGE_ARG("<index>", "Index: an integer >= 0", false);
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("find", "Show index of a param");
|
||||
PRINT_MODULE_USAGE_ARG("<param>", "param name", false);
|
||||
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("lock", "Lock read-only params (reject future set/reset)");
|
||||
}
|
||||
|
||||
int
|
||||
@@ -268,6 +272,9 @@ param_main(int argc, char *argv[])
|
||||
} else if (!strcmp(argv[2], "-a")) {
|
||||
return do_show_all();
|
||||
|
||||
} else if (!strcmp(argv[2], "-l")) {
|
||||
return do_show_locked();
|
||||
|
||||
} else if (!strcmp(argv[2], "-q")) {
|
||||
if (argc >= 4) {
|
||||
return do_show_quiet(argv[3]);
|
||||
@@ -405,6 +412,11 @@ param_main(int argc, char *argv[])
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "lock")) {
|
||||
param_lock_readonly();
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
print_usage();
|
||||
@@ -508,7 +520,7 @@ do_save_default()
|
||||
static int
|
||||
do_show(const char *search_string, bool only_changed)
|
||||
{
|
||||
PX4_INFO_RAW("Symbols: x = used, + = saved, * = unsaved\n");
|
||||
PX4_INFO_RAW("Symbols: x = used, + = saved, * = unsaved, l = locked\n");
|
||||
// also show unused params if we show non-default values only
|
||||
param_foreach(do_show_print, (char *)search_string, only_changed, !only_changed);
|
||||
PX4_INFO_RAW("\n %u/%u parameters used.\n", param_count_used(), param_count());
|
||||
@@ -531,13 +543,30 @@ do_show_for_airframe()
|
||||
static int
|
||||
do_show_all()
|
||||
{
|
||||
PX4_INFO_RAW("Symbols: x = used, + = saved, * = unsaved\n");
|
||||
PX4_INFO_RAW("Symbols: x = used, + = saved, * = unsaved, l = locked\n");
|
||||
param_foreach(do_show_print, nullptr, false, false);
|
||||
PX4_INFO_RAW("\n %u parameters total, %u used.\n", param_count(), param_count_used());
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void
|
||||
do_show_print_locked(void *arg, param_t param)
|
||||
{
|
||||
if (param_is_readonly(param)) {
|
||||
do_show_print(arg, param);
|
||||
}
|
||||
}
|
||||
|
||||
static int
|
||||
do_show_locked()
|
||||
{
|
||||
PX4_INFO_RAW("Symbols: x = used, + = saved, * = unsaved, l = locked\n");
|
||||
param_foreach(do_show_print_locked, nullptr, false, false);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int
|
||||
do_show_quiet(const char *param_name)
|
||||
{
|
||||
@@ -607,8 +636,9 @@ do_show_index(const char *index, bool used_index)
|
||||
return 1;
|
||||
}
|
||||
|
||||
PX4_INFO_RAW("index %d: %c %c %s [%d,%d] : ", i, (param_used(param) ? 'x' : ' '),
|
||||
PX4_INFO_RAW("index %d: %c %c %c %s [%d,%d] : ", i, (param_used(param) ? 'x' : ' '),
|
||||
param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'),
|
||||
param_is_readonly(param) ? 'l' : ' ',
|
||||
param_name(param), param_get_used_index(param), param_get_index(param));
|
||||
|
||||
switch (param_type(param)) {
|
||||
@@ -677,8 +707,9 @@ do_show_print(void *arg, param_t param)
|
||||
}
|
||||
}
|
||||
|
||||
PX4_INFO_RAW("%c %c %s [%d,%d] : ", (param_used(param) ? 'x' : ' '),
|
||||
PX4_INFO_RAW("%c %c %c %s [%d,%d] : ", (param_used(param) ? 'x' : ' '),
|
||||
param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'),
|
||||
param_is_readonly(param) ? 'l' : ' ',
|
||||
param_name(param), param_get_used_index(param), param_get_index(param));
|
||||
|
||||
/*
|
||||
@@ -771,6 +802,11 @@ do_set(const char *name, const char *val, bool fail_on_not_found)
|
||||
return (fail_on_not_found) ? 1 : 0;
|
||||
}
|
||||
|
||||
if (param_is_readonly(param)) {
|
||||
PX4_ERR("Parameter %s is read-only.", name);
|
||||
return 1;
|
||||
}
|
||||
|
||||
/*
|
||||
* Set parameter if type is known and conversion from string to value turns out fine
|
||||
*/
|
||||
@@ -838,6 +874,14 @@ do_set_custom_default(const char *name, const char *val, bool silent_fail)
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
if (param_is_readonly(param)) {
|
||||
if (!silent_fail) {
|
||||
PX4_ERR("Parameter %s is read-only.", name);
|
||||
}
|
||||
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
// Set parameter if type is known and conversion from string to value turns out fine
|
||||
switch (param_type(param)) {
|
||||
case PARAM_TYPE_INT32: {
|
||||
|
||||
Reference in New Issue
Block a user