1515from os import popen as os_popen
1616from sys import exc_info as sys_exc_info
1717from types import TracebackType
18- from typing import Optional , Union
18+ from typing import Callable , Optional , Union
1919
2020from ardupilot_methodic_configurator import _
2121
@@ -107,14 +107,14 @@ def load_param_file_into_dict(param_file: str) -> "ParDict":
107107 msg = f"Missing parameter-value separator: { line } in { param_file } line { i } "
108108 raise SystemExit (msg )
109109 parameter = parameter .strip ()
110- ParDict .validate_parameter (param_file , parameter_dict , i , original_line , comment , parameter , value )
110+ ParDict ._validate_parameter (param_file , parameter_dict , i , original_line , comment , parameter , value )
111111 except UnicodeDecodeError as exp :
112112 msg = f"Fatal error reading { param_file } : { exp } "
113113 raise SystemExit (msg ) from exp
114114 return parameter_dict
115115
116116 @staticmethod
117- def validate_parameter ( # pylint: disable=too-many-arguments, too-many-positional-arguments
117+ def _validate_parameter ( # pylint: disable=too-many-arguments, too-many-positional-arguments
118118 param_file : str ,
119119 parameter_dict : "ParDict" ,
120120 i : int ,
@@ -162,7 +162,7 @@ def missionplanner_sort(item: str) -> tuple[str, ...]:
162162 # Compare the parts separately
163163 return tuple (parts )
164164
165- def format_params (self , file_format : str = "missionplanner" ) -> list [str ]: # pylint: disable=too-many-branches
165+ def _format_params (self , file_format : str = "missionplanner" ) -> list [str ]: # pylint: disable=too-many-branches
166166 """
167167 Formats the parameters in this dictionary into a list of strings.
168168
@@ -217,7 +217,7 @@ def export_to_param(self, filename_out: str, file_format: str = "missionplanner"
217217 file_format: File format ("missionplanner" or "mavproxy").
218218
219219 """
220- formatted_params = self .format_params (file_format )
220+ formatted_params = self ._format_params (file_format )
221221 with open (filename_out , "w" , encoding = "utf-8" ) as output_file :
222222 output_file .writelines (line + "\n " for line in formatted_params )
223223
@@ -278,12 +278,16 @@ def append(self, other: "ParDict") -> None:
278278 for param_name , param_value in other .items ():
279279 self [param_name ] = param_value
280280
281- def remove_if_similar (self , other : "ParDict" ) -> None :
281+ def remove_if_value_is_similar (self , other : "ParDict" ) -> None :
282282 """
283283 Remove parameters from this dictionary if their values match those in another dictionary.
284284
285- This method compares parameter values and removes parameters from the current
286- dictionary if they have the same name and value as parameters in the other dictionary.
285+ This method compares only parameter values and ignores comments when determining similarity.
286+ Parameters from the current dictionary are removed if they have the same name and value
287+ as parameters in the other dictionary, regardless of comment differences.
288+
289+ This is particularly useful when comparing flight controller parameters (which have no comments)
290+ with file parameters (which typically have comments).
287291
288292 Args:
289293 other: Another ParDict to compare against.
@@ -300,93 +304,186 @@ def remove_if_similar(self, other: "ParDict") -> None:
300304 keys_to_remove = []
301305
302306 for param_name , param_value in self .items ():
303- if param_name in other and param_value == other [param_name ]:
307+ if param_name in other and param_value . value == other [param_name ]. value :
304308 keys_to_remove .append (param_name )
305309
306310 # Remove the parameters that matched
307311 for key in keys_to_remove :
308312 del self [key ]
309313
310- def remove_if_value_is_similar (self , other : "ParDict" ) -> None :
314+ @classmethod
315+ def from_file (cls , param_file : str ) -> "ParDict" :
311316 """
312- Remove parameters from this dictionary if their values match those in another dictionary .
317+ Create a ParDict by loading from a parameter file .
313318
314- This method compares only parameter values and ignores comments when determining similarity.
315- Parameters from the current dictionary are removed if they have the same name and value
316- as parameters in the other dictionary, regardless of comment differences.
319+ Args:
320+ param_file: Path to the parameter file.
317321
318- This is particularly useful when comparing flight controller parameters (which have no comments)
319- with file parameters (which typically have comments).
322+ Returns:
323+ A new ParDict loaded from the file.
324+
325+ """
326+ param_dict = ParDict .load_param_file_into_dict (param_file )
327+ return cls (param_dict )
328+
329+ @classmethod
330+ def from_float_dict (cls , param_dict : dict [str , float ], default_comment : str = "" ) -> "ParDict" :
331+ """
332+ Create a ParDict from a dictionary of parameter names to float values.
320333
321334 Args:
322- other: Another ParDict to compare against.
335+ param_dict: Dictionary mapping parameter names to float values.
336+ default_comment: Default comment to apply to all parameters.
323337
324- Raises :
325- TypeError: If other is not an ParDict instance .
338+ Returns :
339+ A new ParDict with Par objects created from the float values .
326340
327341 """
328- if not isinstance (other , ParDict ):
329- msg = _ ("Can only compare with another ParDict instance" )
330- raise TypeError (msg )
342+ result = cls ()
343+ for param_name , param_value in param_dict .items ():
344+ result [param_name ] = Par (float (param_value ), default_comment )
345+ return result
331346
332- # Create a list of keys to remove to avoid modifying dict during iteration
333- keys_to_remove = []
347+ @classmethod
348+ def from_fc_parameters (cls , fc_params : dict [str , float ]) -> "ParDict" :
349+ """
350+ Create a ParDict from flight controller parameters (dict[str, float]).
334351
335- for param_name , param_value in self .items ():
336- if param_name in other and param_value .value == other [param_name ].value :
337- keys_to_remove .append (param_name )
352+ Args:
353+ fc_params: Dictionary of flight controller parameters.
338354
339- # Remove the parameters that matched
340- for key in keys_to_remove :
341- del self [key ]
355+ Returns:
356+ A new ParDict with Par objects created from the flight controller parameters.
357+
358+ """
359+ return cls .from_float_dict (fc_params )
342360
343- def copy (self ) -> "ParDict" :
361+ def _filter_by_defaults (
362+ self , default_params : "ParDict" , tolerance_func : Optional [Callable [[float , float ], bool ]] = None
363+ ) -> "ParDict" :
344364 """
345- Create a shallow copy of the ParDict.
365+ Filter out parameters that have default values within tolerance.
366+
367+ Args:
368+ default_params: ParDict containing default parameter values.
369+ tolerance_func: Function to check if values are within tolerance.
370+ If None, uses exact comparison.
346371
347372 Returns:
348- A new ParDict with the same parameters.
373+ A new ParDict containing only non-default parameters.
349374
350375 """
351- return ParDict (dict (self ))
352-
353- def __repr__ (self ) -> str :
376+ result = ParDict ()
377+ for param_name , param_info in self .items ():
378+ if param_name in default_params :
379+ if tolerance_func :
380+ if not tolerance_func (param_info .value , default_params [param_name ].value ):
381+ result [param_name ] = param_info
382+ elif param_info .value != default_params [param_name ].value :
383+ result [param_name ] = param_info
384+ else :
385+ result [param_name ] = param_info
386+ return result
387+
388+ def _filter_by_readonly (self , doc_dict : dict ) -> "ParDict" :
354389 """
355- Return a string representation of the ParDict.
390+ Filter parameters that are marked as read-only in the documentation.
391+
392+ Args:
393+ doc_dict: Documentation dictionary containing parameter metadata.
356394
357395 Returns:
358- A string representation showing the class name and parameter count .
396+ A new ParDict containing only read-only parameters .
359397
360398 """
361- return f"ParDict({ len (self )} parameters)"
399+ result = ParDict ()
400+ for param_name , param_info in self .items ():
401+ if param_name in doc_dict and doc_dict [param_name ].get ("ReadOnly" , False ):
402+ result [param_name ] = param_info
403+ return result
404+
405+ def _filter_by_calibration (self , doc_dict : dict ) -> "ParDict" :
406+ """
407+ Filter parameters that are marked as calibration parameters in the documentation.
408+
409+ Args:
410+ doc_dict: Documentation dictionary containing parameter metadata.
411+
412+ Returns:
413+ A new ParDict containing only calibration parameters.
362414
363- def __str__ (self ) -> str :
364415 """
365- Return a human-readable string representation of the ParDict.
416+ result = ParDict ()
417+ for param_name , param_info in self .items ():
418+ if param_name in doc_dict and doc_dict [param_name ].get ("Calibration" , False ):
419+ result [param_name ] = param_info
420+ return result
421+
422+ def categorize_by_documentation (
423+ self ,
424+ doc_dict : dict ,
425+ default_params : "ParDict" ,
426+ tolerance_func : Optional [Callable [[float , float ], bool ]] = None ,
427+ ) -> tuple ["ParDict" , "ParDict" , "ParDict" ]:
428+ """
429+ Categorize parameters into read-only, calibration, and other non-default parameters.
430+
431+ Args:
432+ doc_dict: Documentation dictionary containing parameter metadata.
433+ default_params: ParDict containing default parameter values.
434+ tolerance_func: Function to check if values are within tolerance.
366435
367436 Returns:
368- A string showing the parameter count and first few parameter names.
437+ A tuple of three ParDict objects:
438+ - Non-default read-only parameters
439+ - Non-default writable calibration parameters
440+ - Non-default writable non-calibration parameters
369441
370442 """
371- param_count = len (self )
372- if param_count == 0 :
373- return "ParDict(empty)"
443+ non_default_params = self ._filter_by_defaults (default_params , tolerance_func )
374444
375- param_names = list (self .keys ()) if param_count <= 3 else [* list (self .keys ())[:3 ], "..." ]
445+ # there are protected members from a locally created object, so it is OK to access them like this
446+ read_only_params = non_default_params ._filter_by_readonly (doc_dict ) # pylint: disable=protected-access # noqa: SLF001
447+ calibration_params = non_default_params ._filter_by_calibration (doc_dict ) # pylint: disable=protected-access # noqa: SLF001
376448
377- return f"ParDict({ param_count } parameters: { ', ' .join (param_names )} )"
449+ # Non-calibration parameters are those that are not read-only and not calibration
450+ other_params = ParDict ()
451+ for param_name , param_info in non_default_params .items ():
452+ if param_name not in read_only_params and param_name not in calibration_params :
453+ other_params [param_name ] = param_info
378454
379- @classmethod
380- def from_file (cls , param_file : str ) -> "ParDict" :
455+ return read_only_params , calibration_params , other_params
456+
457+ def get_missing_or_different (self , other : "ParDict" ) -> "ParDict" :
381458 """
382- Create a ParDict by loading from a parameter file .
459+ Get parameters that are missing in the other ParDict or have different values .
383460
384461 Args:
385- param_file: Path to the parameter file .
462+ other: The ParDict to compare against .
386463
387464 Returns:
388- A new ParDict loaded from the file .
465+ A new ParDict containing parameters that are missing or different .
389466
390467 """
391- param_dict = ParDict .load_param_file_into_dict (param_file )
392- return cls (param_dict )
468+ result = ParDict ()
469+ for param_name , param in self .items ():
470+ if param_name not in other or other [param_name ].value != param .value :
471+ result [param_name ] = param
472+ return result
473+
474+ def annotate_with_comments (self , comment_lookup : dict [str , str ]) -> "ParDict" :
475+ """
476+ Create a new ParDict with comments added from a lookup table.
477+
478+ Args:
479+ comment_lookup: Dictionary mapping parameter names to their comments.
480+
481+ Returns:
482+ A new ParDict with updated comments.
483+
484+ """
485+ result = ParDict ()
486+ for param_name , param in self .items ():
487+ new_comment = comment_lookup .get (param_name , param .comment or "" )
488+ result [param_name ] = Par (param .value , new_comment )
489+ return result
0 commit comments