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
1 change: 1 addition & 0 deletions ardupilot_methodic_configurator/__main__.py
Original file line number Diff line number Diff line change
Expand Up @@ -578,6 +578,7 @@ def process_component_editor_results(
try:
component_dependent_param_changes = local_filesystem.calculate_derived_and_forced_param_changes(
fc_param_names=fc_param_names,
fc_parameters=flight_controller.fc_parameters or None, # convert empty dict {} to None to indicate no FC connected
)
except ValueError as e:
error_msg = str(e)
Expand Down
22 changes: 13 additions & 9 deletions ardupilot_methodic_configurator/backend_filesystem.py
Original file line number Diff line number Diff line change
Expand Up @@ -845,24 +845,22 @@ def get_eval_variables(self) -> dict[str, dict[str, Any]]:
def calculate_derived_and_forced_param_changes(
self,
fc_param_names: list[str],
fc_parameters: Optional[dict[str, float]] = None,
) -> dict[str, ParDict]:
"""
Compute updated parameter values without mutating the in-memory data model.

This method performs a purely read-only computation phase:
1. For each parameter file, deep-copies the current in-memory state.
2. Applies any values received from the flight controller to the copy.
3. Computes forced and derived parameters and merges them into the copy.
4. Compares each copy against the unmodified original in ``self.file_parameters``.
5. Returns only copies that differ - ``self.file_parameters`` is never mutated.

To apply accepted changes to the data model call
:meth:`apply_computed_changes` with the returned dict. To persist them to
disk call :meth:`save_vehicle_params_to_files` afterwards.

Args:
fc_param_names: List of parameter names that exist in the FC.
If empty or None all parameters are assumed to exist.
fc_parameters: Optional dictionary mapping parameter names to their current FC values.
When provided, enables evaluation of conditions referencing ``fc_parameters``
and allows add-from-FC shorthand ``derived_parameters`` entries
(those without a ``New Value``) to be populated with current FC values.

Returns:
dict[str, ParDict]: Mapping of filenames to their fully-computed ``ParDict``
Expand All @@ -888,8 +886,10 @@ def calculate_derived_and_forced_param_changes(

"""
eval_variables = self.get_eval_variables()
# the eval variables do not contain fc_parameter values
# and that is intentional, the fc_parameters are not to be used in here
if fc_parameters:
eval_variables["fc_parameters"] = fc_parameters
# fc_parameters are intentionally kept in eval_variables only when provided,
# so add-from-FC derived entries without fc_parameters silently skip.

computed_changes: dict[str, ParDict] = {}

Expand All @@ -916,6 +916,10 @@ def calculate_derived_and_forced_param_changes(
param_filename, self.derived_parameters, fc_param_names, target=working
)

# Apply deletions from delete_parameters
for param_name in self.compute_deletions(param_filename, step_dict, eval_variables):
working.pop(param_name, None)

# Include in computed_changes if the working copy differs from the loaded in-memory state
if working.differs_from(param_dict):
computed_changes[param_filename] = working
Expand Down

Large diffs are not rendered by default.

190 changes: 184 additions & 6 deletions ardupilot_methodic_configurator/configuration_steps_ArduCopter.json

Large diffs are not rendered by default.

56 changes: 47 additions & 9 deletions ardupilot_methodic_configurator/configuration_steps_schema.json
Original file line number Diff line number Diff line change
Expand Up @@ -92,19 +92,57 @@
"patternProperties": {
"^[A-Z0-9_]+$": {
"type": "object",
"required": ["New Value", "Change Reason"],
"properties": {
"New Value": {
"type": "string",
"description": "Expression to derive new parameter value"
"oneOf": [
{
"description": "Add-from-FC: include this parameter at its current FC value when the condition holds",
"required": ["if"],
"properties": {
"if": {
"type": "string",
"description": "Python expression; the parameter is added from the FC only when this evaluates to true"
}
},
"additionalProperties": false
},
"Change Reason": {
{
"description": "Computed value: evaluate New Value expression and set the parameter",
"required": ["New Value", "Change Reason"],
"properties": {
"if": {
"type": "string",
"description": "Optional Python expression; if present, the parameter is only applied when this expression evaluates to true"
},
"New Value": {
"type": "string",
"description": "Expression to derive new parameter value"
},
"Change Reason": {
"type": "string",
"description": "Reason for the derived parameter"
}
},
"additionalProperties": false
}
]
}
},
"description": "Parameters whose values are derived from vehicle component data or FC state. An entry with only 'if' means: add the parameter from the FC at its current value when the condition is true."
},
"delete_parameters": {
"type": "object",
"patternProperties": {
"^[A-Z0-9_]+$": {
"type": "object",
"properties": {
"if": {
"type": "string",
"description": "Reason for the derived parameter"
"description": "Optional Python expression; if present, the parameter is only deleted when this expression evaluates to true"
}
}
},
"additionalProperties": false
}
}
},
"description": "Parameters to remove from the configuration file, optionally conditioned on a Python expression"
},
"jump_possible": {
"type": "object",
Expand Down
15 changes: 15 additions & 0 deletions ardupilot_methodic_configurator/configuration_steps_strings.py
Original file line number Diff line number Diff line change
Expand Up @@ -347,6 +347,8 @@ def configuration_steps_descriptions() -> None:
_config_steps_descriptions = _(
"A list of regular expressions to match parameters for automatic import if they have non-default values."
)
_config_steps_descriptions = _("Add-from-FC: include this parameter at its current FC value when the condition holds")
_config_steps_descriptions = _("Computed value: evaluate New Value expression and set the parameter")
_config_steps_descriptions = _("Description of the phase")
_config_steps_descriptions = _("Explanation of why this step is needed")
_config_steps_descriptions = _("Explanation of why this step needs to be done at this point")
Expand All @@ -357,8 +359,21 @@ def configuration_steps_descriptions() -> None:
_config_steps_descriptions = _("Name/description of external tool needed")
_config_steps_descriptions = _("New value for the parameter")
_config_steps_descriptions = _("Optional instructions to display as a popup when entering this step")
_config_steps_descriptions = _(
"Optional Python expression; if present, the parameter is only applied when this expression evaluates to true"
)
_config_steps_descriptions = _(
"Optional Python expression; if present, the parameter is only deleted when this expression evaluates to true"
)
_config_steps_descriptions = _(
"Parameters to remove from the configuration file, optionally conditioned on a Python expression"
)
_config_steps_descriptions = _(
"Parameters whose values are derived from vehicle component data or FC state. An entry with only 'if' means: add the parameter from the FC at its current value when the condition is true."
)
_config_steps_descriptions = _("Phases of the configuration process")
_config_steps_descriptions = _("Previous filenames for this step")
_config_steps_descriptions = _("Python expression; the parameter is added from the FC only when this evaluates to true")
_config_steps_descriptions = _("Reason for changing the parameter")
_config_steps_descriptions = _("Reason for the derived parameter")
_config_steps_descriptions = _("Short description for blog reference")
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,12 @@ def process_configuration_step( # pylint: disable=too-many-locals
elif selected_file in self.local_filesystem.derived_parameters:
# Filter derived parameters that exist in FC (if fc_parameters provided)
fc_param_keys = set(fc_parameters.keys()) if fc_parameters else set()
# Only include params that are already in the file; add-from-FC shorthand entries
# (parameters not yet in file_parameters) are handled separately in the UI layer.
existing_param_names = set(self.local_filesystem.file_parameters.get(selected_file, ParDict()).keys())
for param_name, param in self.local_filesystem.derived_parameters[selected_file].items():
if param_name not in existing_param_names:
continue # add-from-FC shorthand: not yet in file, handled by add-from-FC block
# Only include if no FC filter OR parameter exists in FC
if not fc_param_keys or param_name in fc_param_keys:
derived_params_to_apply[param_name] = param
Expand Down
26 changes: 25 additions & 1 deletion ardupilot_methodic_configurator/data_model_parameter_editor.py
Original file line number Diff line number Diff line change
Expand Up @@ -1684,7 +1684,7 @@ def create_forum_help_zip_workflow(

# frontend_tkinter_parameter_editor_table.py API start

def _repopulate_configuration_step_parameters(
def _repopulate_configuration_step_parameters( # pylint: disable=too-many-locals, too-many-branches
self,
) -> tuple[list[tuple[str, str]], list[tuple[str, str]]]:
"""
Expand Down Expand Up @@ -1754,6 +1754,30 @@ def _repopulate_configuration_step_parameters(
if old_name in self.current_step_parameters:
del self.current_step_parameters[old_name]

# Process delete_parameters and add-from-FC derived entries from configuration steps
step_info = self._local_filesystem.configuration_steps.get(self.current_file, {})
if step_info:
variables = self._config_step_processor.variables.copy()
variables["fc_parameters"] = self.fc_parameters

# Apply add-from-FC: derived entries whose condition passed are already stored in derived_parameters;
# add any that are not yet in current_step_parameters
fc_parameters = self.fc_parameters
for param_name, param in self._local_filesystem.derived_parameters.get(self.current_file, ParDict()).items():
Comment thread
amilcarlucas marked this conversation as resolved.
if param_name not in self.current_step_parameters and param_name in fc_parameters:
self.current_step_parameters[param_name] = self._config_step_processor.create_ardupilot_parameter(
param_name, param, self.current_file, fc_parameters
)
self._added_parameters.add(param_name)

# Apply deletions - remove parameters from domain model and track them.
# Note: compute_deletions is also called in calculate_derived_and_forced_param_changes to
# update the pre-computed filesystem working copy; this separate call updates the live UI domain model.
for param_name in self._local_filesystem.compute_deletions(self.current_file, step_info, variables):
if param_name in self.current_step_parameters:
self._deleted_parameters.add(param_name)
del self.current_step_parameters[param_name]

return ui_errors, ui_infos

def update_parameter_value(
Expand Down
Loading
Loading