4444from ardupilot_methodic_configurator .tempcal_imu import IMUfit
4545
4646
47+ # GNSS MAVLink protocol default value (ArduPilot GPS_TYPE value 5 = MAVLink GPS)
48+ _GNSS_MAVLINK_PROTOCOL_VALUE = "5"
49+ # The rename_connection expression that identifies a GNSS-via-MAVLink step
50+ _GNSS_FC_CONNECTION_RENAME_EXPR = "vehicle_components['GNSS Receiver']['FC Connection']['Type']"
51+
4752@dataclass (frozen = True )
4853class ComponentEditorDeps :
4954 """
@@ -57,7 +62,6 @@ class ComponentEditorDeps:
5762 local_filesystem : LocalFilesystem
5863 fc_parameters : dict [str , float ]
5964
60-
6165# Type aliases for callback functions used in workflow methods
6266AskConfirmationCallback = Callable [[str , str ], bool ] # (title, message) -> bool
6367SelectFileCallback = Callable [[str , list [str ]], Optional [str ]] # (title, filetypes) -> Optional[filename]
@@ -138,6 +142,10 @@ def __init__(
138142 # Track parameters deleted by user (were in original file) or renamed by the system in the current configuration step
139143 self ._deleted_parameters : set [str ] = set ()
140144
145+ # Track connection renames applied for the current step: maps original_file_param_name → current renamed name.
146+ # Used by refresh_current_step_connection_renames() to undo/redo renames without a full rebuild.
147+ self ._connection_renames : dict [str , str ] = {}
148+
141149 self ._at_least_one_changed = False
142150
143151 self ._last_time_asked_to_save : float = 0
@@ -1735,6 +1743,7 @@ def _repopulate_configuration_step_parameters( # pylint: disable=too-many-local
17351743 # Reset tracking sets when navigating to new file
17361744 self ._added_parameters .clear ()
17371745 self ._deleted_parameters .clear ()
1746+ self ._connection_renames .clear ()
17381747
17391748 # Process configuration step and get operations to apply
17401749 self .current_step_parameters , ui_errors , ui_infos , duplicates_to_remove , renames_to_apply , derived_params = (
@@ -1792,6 +1801,9 @@ def _repopulate_configuration_step_parameters( # pylint: disable=too-many-local
17921801 if old_name in self .current_step_parameters :
17931802 del self .current_step_parameters [old_name ]
17941803
1804+ # Track the rename so refresh_current_step_connection_renames() can undo/redo it
1805+ self ._connection_renames [old_name ] = new_name
1806+
17951807 # Process delete_parameters and add-from-FC derived entries from configuration steps
17961808 step_info = self ._local_filesystem .configuration_steps .get (self .current_file , {})
17971809 if step_info :
@@ -2259,30 +2271,33 @@ def _has_component_unsaved_changes(self) -> bool:
22592271
22602272 def refresh_current_step_computed_parameters (self ) -> None :
22612273 """
2262- Recompute derived parameters for the current step after component data changed.
2274+ Recompute derived parameters and connection renames for the current step after component data changed.
22632275
22642276 Unlike _repopulate_configuration_step_parameters(), this performs a lightweight
22652277 in-place update: only the derived parameter *values* are recalculated and patched
2266- into the existing current_step_parameters dict. The full parameter set is NOT
2267- rebuilt from file_parameters and the delete_parameters logic is NOT re-run, so:
2278+ into the existing current_step_parameters dict, and any rename_connection renames
2279+ are re-evaluated and applied. The full parameter set is NOT rebuilt from
2280+ file_parameters and the delete_parameters logic is NOT re-run, so:
22682281 - parameters that were already removed by the delete logic stay removed
22692282 - user edits to non-derived parameters are preserved
22702283 - the 'show only differences' filter does not cause derived params to disappear
22712284 """
22722285 if not self .current_file or self .current_file not in self ._local_filesystem .configuration_steps :
22732286 return
22742287 step_info = self ._local_filesystem .configuration_steps [self .current_file ]
2275- if "derived_parameters" not in step_info :
2288+
2289+ if "derived_parameters" not in step_info and "rename_connection" not in step_info :
22762290 return
22772291
22782292 variables = self ._config_step_processor .variables .copy ()
22792293 if self .fc_parameters :
22802294 variables ["fc_parameters" ] = self .fc_parameters
22812295
2282- # Recompute derived params with the updated vehicle_components dict
2283- self ._local_filesystem .compute_parameters (self .current_file , step_info , "derived" , variables )
2296+ if "derived_parameters" in step_info :
2297+ # Recompute derived params with the updated vehicle_components dict
2298+ self ._local_filesystem .compute_parameters (self .current_file , step_info , "derived" , variables )
22842299
2285- # Patch only the derived values in the existing domain model — no rebuild, no deletions
2300+ # Patch only the derived values in the existing domain model - no rebuild, no deletions
22862301 for param_name , derived_par in self ._local_filesystem .derived_parameters .get (self .current_file , ParDict ()).items ():
22872302 if param_name in self .current_step_parameters :
22882303 existing = self .current_step_parameters [param_name ]
@@ -2303,6 +2318,89 @@ def refresh_current_step_computed_parameters(self) -> None:
23032318 except (ValueError , TypeError ) as e :
23042319 logging_error (_ ("Failed to patch derived parameter %s: %s" ), param_name , str (e ))
23052320
2321+ if "rename_connection" in step_info :
2322+ self ._refresh_current_step_connection_renames (step_info , variables )
2323+
2324+ def _refresh_current_step_connection_renames (self , step_info : dict , variables : dict ) -> None : # pylint: disable=too-many-branches
2325+ """
2326+ Re-evaluate the rename_connection expression and apply any changed renames in-place.
2327+
2328+ Called by refresh_current_step_computed_parameters() after the user edits a component
2329+ field that affects the FC Connection Type. Only the *delta* is applied:
2330+ - Previously renamed parameters whose new target name changed are moved.
2331+ - Parameters that are now targeted for rename but were not before are renamed.
2332+ - Parameters whose rename is no longer applicable are restored to their original name.
2333+ """
2334+ rename_expr = step_info .get ("rename_connection" )
2335+ if not rename_expr :
2336+ return
2337+ is_gnss = "gnss" in self .current_file .lower () and rename_expr == _GNSS_FC_CONNECTION_RENAME_EXPR
2338+
2339+ variables ["new_connection_prefix" ] = rename_expr
2340+ original_params = self ._local_filesystem .file_parameters .get (self .current_file , ParDict ())
2341+
2342+ # Calculate what the renames SHOULD be with the updated component data
2343+ try :
2344+ _duplicates , new_renamed_pairs = self ._config_step_processor .calculate_connection_rename_operations (
2345+ original_params , rename_expr , variables
2346+ )
2347+ except Exception as exc : # pylint: disable=broad-except
2348+ logging_warning (_ ("rename_connection eval failed for %s: %s" ), self .current_file , exc )
2349+ return # evaluation failed — leave current state unchanged
2350+
2351+ new_rename_map : dict [str , str ] = dict (new_renamed_pairs )
2352+
2353+ # Process renames that already exist: update if the target changed
2354+ for orig_name , current_target in list (self ._connection_renames .items ()):
2355+ new_target = new_rename_map .get (orig_name )
2356+ if new_target is None :
2357+ # Rename no longer applicable — restore original name
2358+ if current_target in self .current_step_parameters :
2359+ self ._added_parameters .discard (current_target )
2360+ del self .current_step_parameters [current_target ]
2361+ if orig_name in original_params :
2362+ self .current_step_parameters [orig_name ] = self ._config_step_processor .create_ardupilot_parameter (
2363+ orig_name , original_params [orig_name ], self .current_file , self .fc_parameters
2364+ )
2365+ self ._deleted_parameters .discard (orig_name )
2366+ del self ._connection_renames [orig_name ]
2367+ elif new_target != current_target :
2368+ # Target changed — move the parameter to the new name
2369+ if current_target in self .current_step_parameters :
2370+ self ._added_parameters .discard (current_target )
2371+ del self .current_step_parameters [current_target ]
2372+ if orig_name in original_params :
2373+ self .current_step_parameters [new_target ] = self ._config_step_processor .create_ardupilot_parameter (
2374+ new_target , original_params [orig_name ], self .current_file , self .fc_parameters
2375+ )
2376+ if is_gnss and new_target .endswith ("_PROTOCOL" ):
2377+ self .current_step_parameters [new_target ].set_new_value (
2378+ _GNSS_MAVLINK_PROTOCOL_VALUE , ignore_out_of_range = True
2379+ )
2380+ self ._added_parameters .add (new_target )
2381+ self ._connection_renames [orig_name ] = new_target
2382+ logging_info (_ ("Renamed connection parameter %s → %s" ), current_target , new_target )
2383+
2384+ # Apply renames that are new (not previously tracked)
2385+ for orig_name , new_target in new_rename_map .items ():
2386+ if orig_name in self ._connection_renames :
2387+ continue # already handled above
2388+ if orig_name in original_params :
2389+ # Remove the original (un-renamed) parameter if it is still present
2390+ if orig_name in self .current_step_parameters :
2391+ del self .current_step_parameters [orig_name ]
2392+ self ._deleted_parameters .add (orig_name )
2393+ self .current_step_parameters [new_target ] = self ._config_step_processor .create_ardupilot_parameter (
2394+ new_target , original_params [orig_name ], self .current_file , self .fc_parameters
2395+ )
2396+ if is_gnss and new_target .endswith ("_PROTOCOL" ):
2397+ self .current_step_parameters [new_target ].set_new_value (
2398+ _GNSS_MAVLINK_PROTOCOL_VALUE , ignore_out_of_range = True
2399+ )
2400+ self ._added_parameters .add (new_target )
2401+ self ._connection_renames [orig_name ] = new_target
2402+ logging_info (_ ("Renamed connection parameter %s → %s" ), orig_name , new_target )
2403+
23062404 def revert_vehicle_components (self ) -> None :
23072405 """
23082406 Revert in-memory component data to the last version saved to (or loaded from) disk.
0 commit comments