Skip to content

Commit 439b6be

Browse files
committed
feat(autobackup): Automatically backup FC parameters before the first usage of the AMC software
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
1 parent 297bc05 commit 439b6be

File tree

3 files changed

+25
-0
lines changed

3 files changed

+25
-0
lines changed

ARCHITECTURE.md

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -106,6 +106,8 @@ the following system design requirements were derived:
106106
- Non-default, read-only *reason changed* annotated parameters in, `non-default_read-only.param` file
107107
- Non-default, writable calibrations *reason changed* annotated parameters in `non-default_writable_calibrations.param` file
108108
- Non-default, writable non-calibrations *reason changed* annotated parameters in `non-default_writable_non-calibrations.param` file
109+
- automatically create a parameter backup before the first usage of the software to change parameters [PR #173](https://github.com/ArduPilot/MethodicConfigurator/pull/173)
110+
- 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
109111

110112
#### 7. Customization and Extensibility
111113

ardupilot_methodic_configurator/__main__.py

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -191,6 +191,14 @@ def main() -> None:
191191
imu_tcal_available = "INS_TCAL1_ENABLE" in flight_controller.fc_parameters or not flight_controller.fc_parameters
192192
start_file = local_filesystem.get_start_file(args.n, imu_tcal_available)
193193

194+
if flight_controller.fc_parameters:
195+
local_filesystem.backup_fc_parameters_to_file(
196+
flight_controller.fc_parameters,
197+
"autobackup_00_before_ardupilot_methodic_configurator.param",
198+
overwrite_existing_file=False,
199+
even_if_last_uploaded_filename_exists=False,
200+
)
201+
194202
# Call the GUI function with the starting intermediate parameter file
195203
ParameterEditorWindow(start_file, flight_controller, local_filesystem)
196204

ardupilot_methodic_configurator/backend_filesystem.py

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -575,6 +575,21 @@ def get_start_file(self, explicit_index: int, tcal_available: bool) -> str:
575575
start_file_index = len(files) - 1
576576
return files[start_file_index]
577577

578+
def backup_fc_parameters_to_file(
579+
self,
580+
param_dict: dict[str, float],
581+
filename: str,
582+
overwrite_existing_file: bool = False,
583+
even_if_last_uploaded_filename_exists: bool = True,
584+
) -> None:
585+
if (even_if_last_uploaded_filename_exists or not self.__read_last_uploaded_filename()) and (
586+
overwrite_existing_file or not self.vehicle_configuration_file_exists(filename)
587+
):
588+
Par.export_to_param(
589+
Par.format_params({param: Par(float(value), "") for param, value in param_dict.items()}),
590+
os_path.join(self.vehicle_dir, filename),
591+
)
592+
578593
def get_eval_variables(self) -> dict[str, dict[str, Any]]:
579594
variables = {}
580595
if hasattr(self, "vehicle_components") and self.vehicle_components and "Components" in self.vehicle_components:

0 commit comments

Comments
 (0)