Skip to content

Commit d456cd7

Browse files
committed
feat(param-editor): split non-default params into IDs + non-IDs categories
1 parent f82fc44 commit d456cd7

9 files changed

+132
-47
lines changed

ARCHITECTURE_5_parameter_editor.md

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -359,7 +359,8 @@ At completion, the system generates several summary files:
359359
- `complete.param`: All parameters with change reasons
360360
- `non-default_read-only.param`: Read-only parameters that differ from defaults
361361
- `non-default_writable_calibrations.param`: Vehicle-specific calibrations
362-
- `non-default_writable_non-calibrations.param`: Reusable configuration parameters
362+
- `non-default_writable_ids.param`: Vehicle-specific IDs
363+
- `non-default_writable_non-calibrations_non-ids.param`: Reusable configuration parameters
363364

364365
### Configuration Steps Definition
365366

SYSTEM_REQUIREMENTS.md

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -169,7 +169,8 @@ To semi-automate the steps and processes on that guide the following *system des
169169
- Complete flight controller *reason changed* annotated parameters in `complete.param` file
170170
- Non-default, read-only *reason changed* annotated parameters in, `non-default_read-only.param` file
171171
- Non-default, writable calibrations *reason changed* annotated parameters in `non-default_writable_calibrations.param` file
172-
- Non-default, writable non-calibrations *reason changed* annotated parameters in `non-default_writable_non-calibrations.param` file
172+
- Non-default, writable IDs *reason changed* annotated parameters in `non-default_writable_ids.param` file
173+
- Non-default, writable non-calibrations, non-IDs *reason changed* annotated parameters in `non-default_writable_non-calibrations_non-ids.param` file
173174
- automatically create a parameter backup before the first usage of the software to change parameters [PR #173](https://github.com/ArduPilot/MethodicConfigurator/pull/173)
174175
- Only backs up the parameters if a backup file does not exist and only if AMC has not yet been used to write parameters to the FC
175176

USERMANUAL.md

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -365,7 +365,8 @@ pie title Summary files example
365365
"Unchanged parameters" : 728
366366
"Non-default read-only parameters - non-default_read-only.param" : 8
367367
"Non-default writable sensor calibrations - non-default_writable_calibrations.param" : 71
368-
"Non-default writable non-sensor-calibrations - non-default_writable_non-calibrations.param" : 217
368+
"Non-default writable IDs - non-default_writable_ids.param" : 3
369+
"Non-default writable non-sensor-calibrations, non-IDs - non-default_writable_non-calibrations_non-ids.param" : 217
369370
```
370371

371372
If the diagram above does not display correctly [look here](https://github.com/ArduPilot/MethodicConfigurator/blob/master/USERMANUAL.md#9-completing-the-configuration-process)
@@ -378,24 +379,25 @@ If the diagram above does not display correctly [look here](https://github.com/A
378379
- **Non-default writable sensor calibrations**: These parameters are vehicle-instance dependent and cannot be reused between similar vehicles.
379380
They are typically related to sensor calibration and should be adjusted for each vehicle and are displayed on a yellow background 🟨.
380381

381-
- **Non-default writable non-sensor calibrations**: These parameters can be reused between similar vehicles.
382+
- **Non-default writable IDs**: These parameters are vehicle-instance dependent and cannot be reused between similar vehicles.
383+
384+
- **Non-default writable non-sensor calibrations, non-IDs parameters**: These parameters can be reused between similar vehicles.
382385
They are not related to sensor calibration and are generally applicable to a range of vehicles with the same configuration.
383386

384387
After the summary message box is displayed, the application will write the summary information into separate files for easy reference and documentation. These files include:
385388

386389
- `complete.param`: Contains all parameters contained in the flight controller.
387390
- `non-default_read-only.param`: Contains all non-default read-only 🟥 parameters. You can ignore these.
388391
- `non-default_writable_calibrations.param`: Contains all non-default writable sensor calibration 🟨 parameters. These are non-reusable.
389-
- `non-default_writable_non-calibrations.param`: Contains all non-default writable non-sensor-calibration parameters. These are reusable across similar vehicles.
392+
- `non-default_writable_ids.param`: Contains all non-default writable IDs. These are non-reusable.
393+
- `non-default_writable_non-calibrations_non-ids.param`: Contains all non-default writable non-sensor-calibration, non-IDs parameters. These are reusable across similar vehicles.
390394

391395
The summary files provide a clear overview of the changes made.
392396

393397
The files are also automatically zipped into a file with the same name as the vehicle directory, inside the vehicle directory.
394398

395399
![Parameter files zipped message box](images/Parameter_files_zipped.png)
396400

397-
You should upload this `.zip` file or the `non-default_writable_non-calibrations.param` file to the [How to methodically tune any ArduCopter Blog post](https://discuss.ardupilot.org/t/how-to-methodically-configure-and-tune-any-arducopter/110842/)
398-
399401
Once the summary files are written, the application will close the connection to the flight controller and terminate.
400402

401403
## Configuration Details

ardupilot_methodic_configurator/backend_filesystem.py

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -489,20 +489,21 @@ def annotate_intermediate_comments_to_param_dict(self, param_dict: dict[str, flo
489489
ip_comments = self.__all_intermediate_parameter_file_comments()
490490
return ParDict.from_float_dict(param_dict).annotate_with_comments(ip_comments)
491491

492-
def categorize_parameters(self, param: ParDict) -> tuple[ParDict, ParDict, ParDict]:
492+
def categorize_parameters(self, param: ParDict) -> tuple[ParDict, ParDict, ParDict, ParDict]:
493493
"""
494-
Categorize parameters into three categories based on their default values and documentation attributes.
494+
Categorize parameters into four categories based on their default values and documentation attributes.
495495
496-
This method iterates through the provided ParDict of parameters and categorizes them into three groups:
496+
This method iterates through the provided ParDict of parameters and categorizes them into four groups:
497497
- Non-default, read-only parameters
498498
- Non-default, writable calibrations
499-
- Non-default, writable non-calibrations
499+
- Non-default, writable IDs
500+
- Non-default, writable non-calibrations, non-IDs
500501
501502
Args:
502503
param (ParDict): A ParDict mapping parameter names to their 'Par' objects.
503504
504505
Returns:
505-
Tuple[ParDict, ParDict, ParDict]: A tuple of three ParDict objects.
506+
Tuple[ParDict, ParDict, ParDict, ParDict]: A tuple of four ParDict objects.
506507
Each ParDict represents one of the categories mentioned above.
507508
508509
"""

ardupilot_methodic_configurator/data_model_par_dict.py

Lines changed: 33 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,11 @@
2525
PARAM_NAME_REGEX = r"^[A-Z][A-Z_0-9]*$"
2626
PARAM_NAME_MAX_LEN = 16
2727

28+
# A stable list of known vehicle-instance ID parameters.
29+
# These parameters are typically specific to each vehicle and should not be reused
30+
# across different vehicles without intentional review.
31+
ID_PARAMETER_NAMES = {"SYSID_THISMAV", "SYSID_MYGCS", "FOLL_SYSID"}
32+
2833

2934
class ParamFileError(ValueError):
3035
"""Raised when a .param file contains invalid or malformed data."""
@@ -591,43 +596,64 @@ def _filter_by_calibration(self, doc_dict: dict) -> "ParDict":
591596
}
592597
)
593598

599+
def _filter_by_id(self, _doc_dict: dict) -> "ParDict":
600+
"""
601+
Filter ID parameters.
602+
603+
Args:
604+
_doc_dict: Documentation dictionary containing parameter metadata.
605+
606+
Returns:
607+
A new ParDict containing only ID parameters.
608+
609+
"""
610+
return ParDict(
611+
{
612+
param_name: param_info
613+
for param_name, param_info in self.items()
614+
if param_name in ID_PARAMETER_NAMES
615+
}
616+
)
617+
594618
def categorize_by_documentation(
595619
self,
596620
doc_dict: dict,
597621
default_params: "ParDict",
598622
tolerance_func: Optional[Callable[[float, float], bool]] = None,
599-
) -> tuple["ParDict", "ParDict", "ParDict"]:
623+
) -> tuple["ParDict", "ParDict", "ParDict", "ParDict"]:
600624
"""
601-
Categorize parameters into read-only, calibration, and other non-default parameters.
625+
Categorize parameters into read-only, calibration, IDs and other non-default parameters.
602626
603627
Args:
604628
doc_dict: Documentation dictionary containing parameter metadata.
605629
default_params: ParDict containing default parameter values.
606630
tolerance_func: Function to check if values are within tolerance.
607631
608632
Returns:
609-
A tuple of three ParDict objects:
633+
A tuple of four ParDict objects:
610634
- Non-default read-only parameters
611635
- Non-default writable calibration parameters
612-
- Non-default writable non-calibration parameters
636+
- Non-default writable ID parameters
637+
- Non-default writable non-calibration, non-ID parameters
613638
614639
"""
615640
non_default_params = self._filter_by_defaults(default_params, tolerance_func)
616641

617642
# there are protected members from a locally created object, so it is OK to access them like this
618643
read_only_params = non_default_params._filter_by_readonly(doc_dict) # pylint: disable=protected-access # noqa: SLF001
619644
calibration_params = non_default_params._filter_by_calibration(doc_dict) # pylint: disable=protected-access # noqa: SLF001
645+
id_params = non_default_params._filter_by_id(doc_dict) # pylint: disable=protected-access # noqa: SLF001
620646

621-
# Non-calibration parameters are those that are not read-only and not calibration
647+
# Non-calibration parameters are those that are not read-only, not ID, and not calibration
622648
other_params = ParDict(
623649
{
624650
param_name: param_info
625651
for param_name, param_info in non_default_params.items()
626-
if param_name not in read_only_params and param_name not in calibration_params
652+
if param_name not in read_only_params and param_name not in calibration_params and param_name not in id_params
627653
}
628654
)
629655

630-
return read_only_params, calibration_params, other_params
656+
return read_only_params, calibration_params, id_params, other_params
631657

632658
def annotate_with_comments(self, comment_lookup: dict[str, str]) -> "ParDict":
633659
"""

ardupilot_methodic_configurator/data_model_parameter_editor.py

Lines changed: 32 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -1297,7 +1297,7 @@ def _generate_parameter_summary(self) -> dict[str, ParDict]:
12971297
12981298
Returns:
12991299
dict: Dictionary with parameter categories and their ParDict objects.
1300-
Keys: "complete", "read_only", "calibrations", "non_calibrations"
1300+
Keys: "complete", "read_only", "calibrations", "ids", "non_calibrations_non_ids"
13011301
13021302
"""
13031303
# Get annotated FC parameters
@@ -1309,17 +1309,23 @@ def _generate_parameter_summary(self) -> dict[str, ParDict]:
13091309

13101310
# Categorize parameters using filesystem logic
13111311
categorized = self._local_filesystem.categorize_parameters(annotated_fc_parameters)
1312-
if not categorized or len(categorized) != 3:
1312+
if not categorized or len(categorized) != 4:
13131313
# Return empty dict if categorization fails or returns empty tuple
13141314
return {}
13151315

1316-
non_default__read_only_params, non_default__writable_calibrations, non_default__writable_non_calibrations = categorized
1316+
(
1317+
non_default__read_only_params,
1318+
non_default__writable_calibrations,
1319+
non_default__ids,
1320+
non_default__writable_non_calibrations_non_ids,
1321+
) = categorized
13171322

13181323
return {
13191324
"complete": annotated_fc_parameters,
13201325
"read_only": non_default__read_only_params,
13211326
"calibrations": non_default__writable_calibrations,
1322-
"non_calibrations": non_default__writable_non_calibrations,
1327+
"ids": non_default__ids,
1328+
"non_calibrations_non_ids": non_default__writable_non_calibrations_non_ids,
13231329
}
13241330

13251331
def _get_parameter_summary_msg(self, parameter_summary: dict[str, ParDict]) -> str:
@@ -1340,12 +1346,14 @@ def _get_parameter_summary_msg(self, parameter_summary: dict[str, ParDict]) -> s
13401346
nr_total_params = len(parameter_summary.get("complete", {}))
13411347
nr_non_default__read_only_params = len(parameter_summary.get("read_only", {}))
13421348
nr_non_default__writable_calibrations = len(parameter_summary.get("calibrations", {}))
1343-
nr_non_default__writable_non_calibrations = len(parameter_summary.get("non_calibrations", {}))
1349+
nr_non_default__ids = len(parameter_summary.get("ids", {}))
1350+
nr_non_default__writable_non_calibrations_non_ids = len(parameter_summary.get("non_calibrations_non_ids", {}))
13441351
nr_unchanged_params = (
13451352
nr_total_params
13461353
- nr_non_default__read_only_params
13471354
- nr_non_default__writable_calibrations
1348-
- nr_non_default__writable_non_calibrations
1355+
- nr_non_default__ids
1356+
- nr_non_default__writable_non_calibrations_non_ids
13491357
)
13501358

13511359
# Format the summary message
@@ -1356,7 +1364,9 @@ def _get_parameter_summary_msg(self, parameter_summary: dict[str, ParDict]) -> s
13561364
"ignore these, you can not change them\n\n"
13571365
"{nr_non_default__writable_calibrations} non-default writable sensor-calibrations - "
13581366
"non-reusable between vehicles\n\n"
1359-
"{nr_non_default__writable_non_calibrations} non-default writable non-sensor-calibrations - "
1367+
"{nr_non_default__ids} non-default ID parameters - "
1368+
"vehicle-instance dependent non-reusable values; review before reuse\n\n"
1369+
"{nr_non_default__writable_non_calibrations_non_ids} non-default writable non-sensor-calibrations non-IDs - "
13601370
"these can be reused between similar vehicles"
13611371
)
13621372

@@ -1365,7 +1375,8 @@ def _get_parameter_summary_msg(self, parameter_summary: dict[str, ParDict]) -> s
13651375
nr_unchanged_params=nr_unchanged_params,
13661376
nr_non_default__read_only_params=nr_non_default__read_only_params,
13671377
nr_non_default__writable_calibrations=nr_non_default__writable_calibrations,
1368-
nr_non_default__writable_non_calibrations=nr_non_default__writable_non_calibrations,
1378+
nr_non_default__ids=nr_non_default__ids,
1379+
nr_non_default__writable_non_calibrations_non_ids=nr_non_default__writable_non_calibrations_non_ids,
13691380
)
13701381

13711382
def write_summary_files_workflow(
@@ -1405,7 +1416,8 @@ def write_summary_files_workflow(
14051416
complete_params = parameter_summary["complete"]
14061417
read_only_params = parameter_summary["read_only"]
14071418
calibration_params = parameter_summary["calibrations"]
1408-
non_calibration_params = parameter_summary["non_calibrations"]
1419+
id_params = parameter_summary["ids"]
1420+
non_calibration_non_ids_params = parameter_summary["non_calibrations_non_ids"]
14091421

14101422
# Write individual summary files
14111423
wrote_complete = self._write_single_summary_file_workflow(
@@ -1420,9 +1432,15 @@ def write_summary_files_workflow(
14201432
annotate_doc=False,
14211433
ask_confirmation=ask_confirmation,
14221434
)
1423-
wrote_non_calibrations = self._write_single_summary_file_workflow(
1424-
non_calibration_params,
1425-
"non-default_writable_non-calibrations.param",
1435+
wrote_ids = self._write_single_summary_file_workflow(
1436+
id_params,
1437+
"non-default_writable_ids.param",
1438+
annotate_doc=False,
1439+
ask_confirmation=ask_confirmation,
1440+
)
1441+
wrote_non_calibrations_non_ids = self._write_single_summary_file_workflow(
1442+
non_calibration_non_ids_params,
1443+
"non-default_writable_non-calibrations_non-ids.param",
14261444
annotate_doc=False,
14271445
ask_confirmation=ask_confirmation,
14281446
)
@@ -1432,7 +1450,8 @@ def write_summary_files_workflow(
14321450
(wrote_complete, "complete.param"),
14331451
(wrote_read_only, "non-default_read-only.param"),
14341452
(wrote_calibrations, "non-default_writable_calibrations.param"),
1435-
(wrote_non_calibrations, "non-default_writable_non-calibrations.param"),
1453+
(wrote_ids, "non-default_writable_ids.param"),
1454+
(wrote_non_calibrations_non_ids, "non-default_writable_non-calibrations_non-ids.param"),
14361455
]
14371456

14381457
# Write zip file with user confirmation

tests/test_backend_filesystem.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -634,11 +634,12 @@ def test_categorize_parameters(self) -> None:
634634

635635
test_params = ParDict({"PARAM1": Par(2.0), "PARAM2": Par(2.0), "PARAM3": Par(2.0)})
636636

637-
readonly, calibration, other = lfs.categorize_parameters(test_params)
637+
readonly, calibration, ids, other = lfs.categorize_parameters(test_params)
638638

639639
assert "PARAM1" in readonly
640640
assert "PARAM2" in calibration
641641
assert "PARAM3" in other
642+
assert not ids
642643

643644
def test_calculate_derived_and_forced_param_changes(self) -> None:
644645
lfs = LocalFilesystem(

0 commit comments

Comments
 (0)