diff --git a/ardupilot_methodic_configurator/__main__.py b/ardupilot_methodic_configurator/__main__.py index 76adb10e7..4b5c9d527 100755 --- a/ardupilot_methodic_configurator/__main__.py +++ b/ardupilot_methodic_configurator/__main__.py @@ -36,6 +36,7 @@ from ardupilot_methodic_configurator.backend_flightcontroller import FlightController from ardupilot_methodic_configurator.backend_internet import verify_and_open_url from ardupilot_methodic_configurator.common_arguments import add_common_arguments +from ardupilot_methodic_configurator.data_model_par_dict import ParDict from ardupilot_methodic_configurator.data_model_software_updates import UpdateManager, check_for_software_updates from ardupilot_methodic_configurator.data_model_vehicle_project import VehicleProjectManager from ardupilot_methodic_configurator.frontend_tkinter_component_editor import ComponentEditorWindow @@ -53,7 +54,7 @@ def __init__(self, args: argparse.Namespace) -> None: self.args = args self.flight_controller: FlightController = None # type: ignore[assignment] self.vehicle_type: str = "" - self.param_default_values: dict = {} + self.param_default_values: ParDict = ParDict() self.local_filesystem: LocalFilesystem = None # type: ignore[assignment] self.vehicle_project_manager: Union[VehicleProjectManager, None] = None self.param_default_values_dirty: bool = False @@ -167,7 +168,8 @@ def initialize_flight_controller_and_filesystem(state: ApplicationState) -> None # Get default parameter values from flight controller if state.flight_controller.master is not None or state.args.device == "test": fciw = FlightControllerInfoWindow(state.flight_controller) - state.param_default_values = fciw.get_param_default_values() + default_values = fciw.get_param_default_values() + state.param_default_values = ParDict(default_values) if default_values else ParDict() # Initialize local filesystem try: @@ -218,7 +220,8 @@ def vehicle_directory_selection(state: ApplicationState) -> Union[VehicleDirecto state.flight_controller.reset_and_reconnect() if state.flight_controller.master is not None or state.args.device == "test": fciw = FlightControllerInfoWindow(state.flight_controller) - state.param_default_values = fciw.get_param_default_values() + default_values = fciw.get_param_default_values() + state.param_default_values = ParDict(default_values) if default_values else ParDict() return vehicle_dir_window @@ -474,10 +477,12 @@ def parameter_editor_and_uploader(state: ApplicationState) -> None: } if state.flight_controller.fc_parameters and state.flight_controller.info.flight_sw_version.startswith("4.6."): for filename in state.local_filesystem.file_parameters: - state.local_filesystem.file_parameters[filename] = { - param_upgrade_dict.get(parameter_name, parameter_name): par - for parameter_name, par in state.local_filesystem.file_parameters[filename].items() - } + state.local_filesystem.file_parameters[filename] = ParDict( + { + param_upgrade_dict.get(parameter_name, parameter_name): par + for parameter_name, par in state.local_filesystem.file_parameters[filename].items() + } + ) # Call the GUI function with the starting intermediate parameter file ParameterEditorWindow(start_file, state.flight_controller, state.local_filesystem) diff --git a/ardupilot_methodic_configurator/annotate_params.py b/ardupilot_methodic_configurator/annotate_params.py index 01e995c09..f48aea114 100755 --- a/ardupilot_methodic_configurator/annotate_params.py +++ b/ardupilot_methodic_configurator/annotate_params.py @@ -30,10 +30,7 @@ import re from os import environ as os_environ from os import path as os_path -from os import popen as os_popen -from sys import exc_info as sys_exc_info from sys import exit as sys_exit -from types import TracebackType from typing import Any, Optional, Union from xml.etree import ElementTree as ET # no parsing, just data-structure manipulation @@ -41,15 +38,14 @@ from argcomplete.completers import FilesCompleter from defusedxml import ElementTree as DET # noqa: N814, just parsing, no data-structure manipulation +from ardupilot_methodic_configurator.data_model_par_dict import PARAM_NAME_MAX_LEN, PARAM_NAME_REGEX, ParDict + # URL of the XML file BASE_URL = "https://autotest.ardupilot.org/Parameters/" PARAM_DEFINITION_XML_FILE = "apm.pdef.xml" LUA_PARAM_DEFINITION_XML_FILE = "24_inflight_magnetometer_fit_setup.pdef.xml" -# ArduPilot parameter names start with a capital letter and can have capital letters, numbers and _ -PARAM_NAME_REGEX = r"^[A-Z][A-Z_0-9]*" -PARAM_NAME_MAX_LEN = 16 VERSION = "1.0" # mypy: disable-error-code="unused-ignore" @@ -137,235 +133,6 @@ def check_max_line_length(value: int) -> int: return args -class Par: - """ - Represents a parameter with a value and an optional comment. - - Attributes: - value (float): The value of the parameter. - comment (Optional[str]): An optional comment associated with the parameter. - - """ - - def __init__(self, value: float, comment: Optional[str] = None) -> None: - self.value = value - self.comment = comment - - def __eq__(self, other: object) -> bool: - """Equality operation.""" - if isinstance(other, Par): - return self.value == other.value and self.comment == other.comment - return False - - def __hash__(self) -> int: - """Hash operation for using Par objects in sets and as dict keys.""" - return hash((self.value, self.comment)) - - @staticmethod - def load_param_file_into_dict(param_file: str) -> dict[str, "Par"]: - """ - Loads an ArduPilot parameter file into a dictionary with name, value pairs. - - Args: - param_file (str): The name of the parameter file to load. - - Returns: - dict: A dictionary containing the parameters from the file. - - """ - parameter_dict: dict[str, Par] = {} - try: - with open(param_file, encoding="utf-8") as f_handle: - for i, f_line in enumerate(f_handle, start=1): - original_line = f_line - line = f_line.strip() - comment = None - if not line: - continue # skip empty lines - if line[0] == "#": - continue # skip comments - if "#" in line: - line, comment = line.split("#", 1) # strip trailing comments - comment = comment.strip() - if "," in line: - # parse mission planner style parameter files - parameter, value = line.split(",", 1) - elif " " in line: - # parse mavproxy style parameter files - parameter, value = line.split(" ", 1) - elif "\t" in line: - parameter, value = line.split("\t", 1) - else: - msg = f"Missing parameter-value separator: {line} in {param_file} line {i}" - raise SystemExit(msg) - parameter = parameter.strip() - Par.validate_parameter(param_file, parameter_dict, i, original_line, comment, parameter, value) - except UnicodeDecodeError as exp: - msg = f"Fatal error reading {param_file}: {exp}" - raise SystemExit(msg) from exp - return parameter_dict - - @staticmethod - def validate_parameter( # pylint: disable=too-many-arguments, too-many-positional-arguments - param_file: str, - parameter_dict: dict[str, "Par"], - i: int, - original_line: str, - comment: Union[None, str], - parameter_name: str, - value: str, - ) -> None: - if len(parameter_name) > PARAM_NAME_MAX_LEN: - msg = f"Too long parameter name: {parameter_name} in {param_file} line {i}" - raise SystemExit(msg) - if not re.match(PARAM_NAME_REGEX, parameter_name): - msg = f"Invalid characters in parameter name {parameter_name} in {param_file} line {i}" - raise SystemExit(msg) - if parameter_name in parameter_dict: - msg = f"Duplicated parameter {parameter_name} in {param_file} line {i}" - raise SystemExit(msg) - try: - fvalue = float(value.strip()) - parameter_dict[parameter_name] = Par(fvalue, comment) - except ValueError as exc: - msg = f"Invalid parameter value {value} in {param_file} line {i}" - raise SystemExit(msg) from exc - except OSError as exc: - _exc_type, exc_value, exc_traceback = sys_exc_info() - if isinstance(exc_traceback, TracebackType): - fname = os_path.split(exc_traceback.tb_frame.f_code.co_filename)[1] - logging.critical("in line %s of file %s: %s", exc_traceback.tb_lineno, fname, exc_value) - msg = f"Caused by line {i} of file {param_file}: {original_line}" - raise SystemExit(msg) from exc - - @staticmethod - def missionplanner_sort(item: str) -> tuple[str, ...]: - """ - Sorts a parameter name according to the rules defined in the Mission Planner software. - - Args: - item: The parameter name to sort. - - Returns: - A tuple representing the sorted parameter name. - - """ - parts = item.split("_") # Split the parameter name by underscore - # Compare the parts separately - return tuple(parts) - - @staticmethod - def format_params(param_dict: dict[str, "Par"], file_format: str = "missionplanner") -> list[str]: # pylint: disable=too-many-branches - """ - Formats the parameters in the provided dictionary into a list of strings. - - Each string in the returned list is a formatted representation of a parameter, - consisting of the parameter's name, its value, and optionally its comment. - The comment is included if it is present in the parameter's 'Par' object. - - Args: - param_dict (Dict[str, 'Par']): A dictionary of 'Par' objects. - Each key is a parameter name and each value is a 'Par' object. - Par can be a simple float or a Par object with a comment. - file_format (str): Can be "missionplanner" or "mavproxy" - - Returns: - List[str]: A list of strings, each string representing a parameter from the input dictionary - in the format "name,value # comment". - - """ - if file_format == "missionplanner": - param_dict = dict(sorted(param_dict.items(), key=lambda x: Par.missionplanner_sort(x[0]))) # sort alphabetically - elif file_format == "mavproxy": - param_dict = dict(sorted(param_dict.items())) # sort in ASCIIbetical order - else: - msg = f"ERROR: Unsupported file format {file_format}" - raise SystemExit(msg) - - formatted_params = [] - if file_format == "missionplanner": - for key, parameter in param_dict.items(): - if isinstance(parameter, Par): - if parameter.comment: - formatted_params.append( - f"{key},{format(parameter.value, '.6f').rstrip('0').rstrip('.')} # {parameter.comment}" - ) - else: - formatted_params.append(f"{key},{format(parameter.value, '.6f').rstrip('0').rstrip('.')}") - else: - formatted_params.append(f"{key},{format(parameter, '.6f').rstrip('0').rstrip('.')}") - elif file_format == "mavproxy": - for key, parameter in param_dict.items(): - if isinstance(parameter, Par): - if parameter.comment: - formatted_params.append(f"{key:<16} {parameter.value:<8.6f} # {parameter.comment}") - else: - formatted_params.append(f"{key:<16} {parameter.value:<8.6f}") - else: - formatted_params.append(f"{key:<16} {parameter:<8.6f}") - return formatted_params - - @staticmethod - def export_to_param(formatted_params: list[str], filename_out: str) -> None: - """ - Exports a list of formatted parameters to an ArduPilot parameter file. - - Args: - formatted_params (List[str]): The list of formatted parameters to export. - filename_out (str): The output filename. - - Returns: - None - - """ - if not formatted_params: - return - try: - # Ensure newline character is LF, even on windows - with open(filename_out, "w", encoding="utf-8", newline="\n") as output_file: - output_file.writelines(line + "\n" for line in formatted_params) - except OSError as e: - msg = f"ERROR: writing to file {filename_out}: {e}" - raise SystemExit(msg) from e - - @staticmethod - def print_out(formatted_params: list[str], name: str) -> None: - """ - Print out the contents of the provided list. - - If the list is too large, print only the ones that fit on the screen and - wait for user input to continue. - - Args: - formatted_params (List[str]): The list of formatted parameters to print. - name (str): A descriptive string for the list contents - - Returns: - None - - """ - if not formatted_params: - return - - rows_str = "100" # number of lines to display before waiting for user input - - # Get the size of the terminal - if __name__ == "__main__": - rows_str, _columns = os_popen("stty size", "r").read().split() # noqa: S605, S607 - - # Convert rows to integer - rows = int(rows_str) - 2 # -2 for the next print and the input line - - # Convert rows - print(f"\n{name} has {len(formatted_params)} parameters:") # noqa: T201 - for i, line in enumerate(formatted_params): - if i % rows == 0 and __name__ == "__main__": - input(f"\n{name} list is long hit enter to continue") - rows_str, _columns = os_popen("stty size", "r").read().split() # noqa: S605, S607 - rows = int(rows_str) - 2 # -2 for the next print and the input line - print(line) # noqa: T201 - - def get_xml_data(base_url: str, directory: str, filename: str, vehicle_type: str) -> ET.Element: # pylint: disable=too-many-locals """ Fetches XML data from a local file or a URL. @@ -461,11 +228,11 @@ def get_env_proxies() -> Union[dict[str, str], None]: return proxies -def load_default_param_file(directory: str) -> dict[str, "Par"]: - param_default_dict: dict[str, Par] = {} +def load_default_param_file(directory: str) -> ParDict: + param_default_dict: ParDict = ParDict() # Load parameter default values if the 00_default.param file exists try: - param_default_dict = Par.load_param_file_into_dict(os_path.join(directory, "00_default.param")) + param_default_dict = ParDict.from_file(os_path.join(directory, "00_default.param")) except FileNotFoundError: logging.warning("Default parameter file 00_default.param not found. No default values will be annotated.") logging.warning("Create one by using the command ./extract_param_defaults.py log_file.bin > 00_default.param") @@ -647,20 +414,24 @@ def extract_parameter_name_and_validate(line: str, filename: str, line_nr: int) SystemExit: If the line is invalid or the parameter name is too long or invalid. """ - # Extract the parameter name - match = re.match(PARAM_NAME_REGEX, line) + # Extract the parameter name from the line (until we hit a separator) + # Create a regex to extract parameter name followed by separator + param_line_pattern = r"^([A-Z][A-Z_0-9]*)[,\s\t]" + match = re.match(param_line_pattern, line) if match: - param_name = match.group(0) + param_name = match.group(1) else: logging.critical("Invalid line %d in file %s: %s", line_nr, filename, line) msg = "Invalid line in input file" raise SystemExit(msg) - param_len = len(param_name) - param_sep = line[param_len] # the character following the parameter name must be a separator - if param_sep not in {",", " ", "\t"}: + + # Validate the extracted parameter name against the strict parameter name regex + if not re.match(PARAM_NAME_REGEX, param_name): logging.critical("Invalid parameter name %s on line %d in file %s", param_name, line_nr, filename) msg = "Invalid parameter name" raise SystemExit(msg) + + param_len = len(param_name) if param_len > PARAM_NAME_MAX_LEN: logging.critical("Too long parameter name on line %d in file %s", line_nr, filename) msg = "Too long parameter name" diff --git a/ardupilot_methodic_configurator/backend_filesystem.py b/ardupilot_methodic_configurator/backend_filesystem.py index 0b95862e1..b2d8a8bfa 100644 --- a/ardupilot_methodic_configurator/backend_filesystem.py +++ b/ardupilot_methodic_configurator/backend_filesystem.py @@ -36,7 +36,6 @@ from ardupilot_methodic_configurator import _ from ardupilot_methodic_configurator.annotate_params import ( PARAM_DEFINITION_XML_FILE, - Par, format_columns, get_xml_dir, get_xml_url, @@ -48,6 +47,7 @@ from ardupilot_methodic_configurator.backend_filesystem_configuration_steps import ConfigurationSteps from ardupilot_methodic_configurator.backend_filesystem_program_settings import ProgramSettings from ardupilot_methodic_configurator.backend_filesystem_vehicle_components import VehicleComponents +from ardupilot_methodic_configurator.data_model_par_dict import Par, ParDict TOOLTIP_MAX_LENGTH = 105 @@ -98,14 +98,14 @@ def __init__( # pylint: disable=too-many-arguments, too-many-positional-argumen allow_editing_template_files: bool, save_component_to_system_templates: bool, ) -> None: - self.file_parameters: dict[str, dict[str, Par]] = {} + self.file_parameters: dict[str, ParDict] = {} VehicleComponents.__init__(self, save_component_to_system_templates) ConfigurationSteps.__init__(self, vehicle_dir, vehicle_type) ProgramSettings.__init__(self) self.vehicle_type = vehicle_type self.fw_version = fw_version self.allow_editing_template_files = allow_editing_template_files - self.param_default_dict: dict[str, Par] = {} + self.param_default_dict: ParDict = ParDict() self.vehicle_dir = vehicle_dir self.doc_dict: dict[str, Any] = {} if vehicle_dir is not None: @@ -319,7 +319,7 @@ def __extend_and_reformat_parameter_documentation_metadata(self) -> None: # pyl prefix_parts_sorted += [f"Default: {default_value}"] param_info["doc_tooltip_sorted_numerically"] = ("\n").join(prefix_parts_sorted) - def read_params_from_files(self) -> dict[str, dict[str, "Par"]]: + def read_params_from_files(self) -> dict[str, ParDict]: """ Reads intermediate parameter files from a directory and stores their contents in a dictionary. @@ -328,11 +328,10 @@ def read_params_from_files(self) -> dict[str, dict[str, "Par"]]: Files named '00_default.param' and '01_ignore_readonly.param' are ignored. Returns: - - Dict[str, Dict[str, 'Par']]: A dictionary with filenames as keys and as values - a dictionary with (parameter names, values) pairs. + - Dict[str, ParDict]: A dictionary with filenames as keys and ParDict as values. """ - parameters: dict[str, dict[str, Par]] = {} + parameters: dict[str, ParDict] = {} if os_path.isdir(self.vehicle_dir): # Regular expression pattern for filenames starting with two digits followed by an underscore and ending in .param pattern = re_compile(r"^\d{2}_.*\.param$") @@ -341,7 +340,7 @@ def read_params_from_files(self) -> dict[str, dict[str, "Par"]]: if pattern.match(filename): if filename in {"00_default.param", "01_ignore_readonly.param"}: continue - parameters[filename] = Par.load_param_file_into_dict(os_path.join(self.vehicle_dir, filename)) + parameters[filename] = ParDict.from_file(os_path.join(self.vehicle_dir, filename)) else: logging_error(_("Error: %s is not a directory."), self.vehicle_dir) return parameters @@ -367,7 +366,7 @@ def str_to_bool(s: str) -> Optional[bool]: return False return None - def export_to_param(self, params: dict[str, "Par"], filename_out: str, annotate_doc: bool = True) -> None: + def export_to_param(self, params: ParDict, filename_out: str, annotate_doc: bool = True) -> None: """ Exports a dictionary of parameters to a .param file and optionally annotates the documentation. @@ -375,12 +374,12 @@ def export_to_param(self, params: dict[str, "Par"], filename_out: str, annotate_ writes the string to the specified output file, and optionally updates the parameter documentation. Args: - params (Dict[str, 'Par']): A dictionary of parameters to export. + params (ParDict): A ParDict of parameters to export. filename_out (str): The name of the output file. annotate_doc (bool, optional): Whether to update the parameter documentation. Default is True. """ - Par.export_to_param(Par.format_params(params), os_path.join(self.vehicle_dir, filename_out)) + params.export_to_param(os_path.join(self.vehicle_dir, filename_out)) if annotate_doc: update_parameter_documentation( self.doc_dict, os_path.join(self.vehicle_dir, filename_out), "missionplanner", self.param_default_dict @@ -419,63 +418,42 @@ def __all_intermediate_parameter_file_comments(self) -> dict[str, str]: ret[param] = info.comment return ret - def annotate_intermediate_comments_to_param_dict(self, param_dict: dict[str, float]) -> dict[str, "Par"]: + def annotate_intermediate_comments_to_param_dict(self, param_dict: dict[str, float]) -> ParDict: """ Annotates comments from intermediate parameter files to a parameter value-only dictionary. This function takes a dictionary of parameters with only values and adds comments from - intermediate parameter files to create a new dictionary where each parameter is represented + intermediate parameter files to create a new ParDict where each parameter is represented by a 'Par' object containing both the value and the comment. Args: param_dict (Dict[str, float]): A dictionary of parameters with only values. Returns: - Dict[str, 'Par']: A dictionary of parameters with intermediate parameter file comments. + ParDict: A ParDict of parameters with intermediate parameter file comments. """ - ret = {} ip_comments = self.__all_intermediate_parameter_file_comments() - for param, value in param_dict.items(): - ret[param] = Par(float(value), ip_comments.get(param, "")) - return ret + return ParDict.from_float_dict(param_dict).annotate_with_comments(ip_comments) - def categorize_parameters(self, param: dict[str, "Par"]) -> tuple[dict[str, "Par"], dict[str, "Par"], dict[str, "Par"]]: + def categorize_parameters(self, param: ParDict) -> tuple[ParDict, ParDict, ParDict]: """ Categorize parameters into three categories based on their default values and documentation attributes. - This method iterates through the provided dictionary of parameters and categorizes them into three groups: + This method iterates through the provided ParDict of parameters and categorizes them into three groups: - Non-default, read-only parameters - Non-default, writable calibrations - Non-default, writable non-calibrations Args: - param (Dict[str, 'Par']): A dictionary mapping parameter names to their 'Par' objects. + param (ParDict): A ParDict mapping parameter names to their 'Par' objects. Returns: - Tuple[Dict[str, "Par"], Dict[str, "Par"], Dict[str, "Par"]]: A tuple of three dictionaries. - Each dictionary represents one of the categories mentioned above. + Tuple[ParDict, ParDict, ParDict]: A tuple of three ParDict objects. + Each ParDict represents one of the categories mentioned above. """ - non_default__read_only_params = {} - non_default__writable_calibrations = {} - non_default__writable_non_calibrations = {} - for param_name, param_info in param.items(): - if param_name in self.param_default_dict and is_within_tolerance( - param_info.value, self.param_default_dict[param_name].value - ): - continue # parameter has a default value, ignore it - - if param_name in self.doc_dict and self.doc_dict[param_name].get("ReadOnly", False): - non_default__read_only_params[param_name] = param_info - continue - - if param_name in self.doc_dict and self.doc_dict[param_name].get("Calibration", False): - non_default__writable_calibrations[param_name] = param_info - continue - non_default__writable_non_calibrations[param_name] = param_info - - return non_default__read_only_params, non_default__writable_calibrations, non_default__writable_non_calibrations + return param.categorize_by_documentation(self.doc_dict, self.param_default_dict, is_within_tolerance) @staticmethod def get_directory_name_from_full_path(full_path: str) -> str: @@ -741,10 +719,8 @@ def backup_fc_parameters_to_file( if (even_if_last_uploaded_filename_exists or not self.__read_last_uploaded_filename()) and ( overwrite_existing_file or not self.vehicle_configuration_file_exists(filename) ): - Par.export_to_param( - Par.format_params({param: Par(float(value), "") for param, value in param_dict.items()}), - os_path.join(self.vehicle_dir, filename), - ) + param_dict_as_par = ParDict({param: Par(float(value), "") for param, value in param_dict.items()}) + param_dict_as_par.export_to_param(os_path.join(self.vehicle_dir, filename)) def get_eval_variables(self) -> dict[str, dict[str, Any]]: variables = {} @@ -803,7 +779,7 @@ def update_and_export_vehicle_params_from_fc( return "" def merge_forced_or_derived_parameters( - self, filename: str, new_parameters: dict[str, dict[str, Par]], existing_fc_params: Optional[list[str]] + self, filename: str, new_parameters: dict[str, ParDict], existing_fc_params: Optional[list[str]] ) -> bool: """ Merge forced or derived parameter values in the self.file_parameter list. @@ -830,18 +806,17 @@ def merge_forced_or_derived_parameters( self.file_parameters[filename][param_name] = param return at_least_one_param_changed - def write_param_default_values(self, param_default_values: dict[str, "Par"]) -> bool: - param_default_values = dict(sorted(param_default_values.items())) + def write_param_default_values(self, param_default_values: ParDict) -> bool: + param_default_values = ParDict(dict(sorted(param_default_values.items()))) if self.param_default_dict != param_default_values: self.param_default_dict = param_default_values return True return False - def write_param_default_values_to_file( - self, param_default_values: dict[str, "Par"], filename: str = "00_default.param" - ) -> None: + def write_param_default_values_to_file(self, param_default_values: ParDict, filename: str = "00_default.param") -> None: if self.write_param_default_values(param_default_values): - Par.export_to_param(Par.format_params(self.param_default_dict), os_path.join(self.vehicle_dir, filename)) + self.file_parameters[filename] = param_default_values + self.param_default_dict.export_to_param(os_path.join(self.vehicle_dir, filename)) def get_download_url_and_local_filename(self, selected_file: str) -> tuple[str, str]: if ( diff --git a/ardupilot_methodic_configurator/backend_filesystem_configuration_steps.py b/ardupilot_methodic_configurator/backend_filesystem_configuration_steps.py index 9f1ac4a50..9a5f9e87a 100644 --- a/ardupilot_methodic_configurator/backend_filesystem_configuration_steps.py +++ b/ardupilot_methodic_configurator/backend_filesystem_configuration_steps.py @@ -22,7 +22,7 @@ from jsonschema.exceptions import ValidationError from ardupilot_methodic_configurator import _ -from ardupilot_methodic_configurator.annotate_params import Par +from ardupilot_methodic_configurator.data_model_par_dict import Par, ParDict class ConfigurationSteps: @@ -42,8 +42,8 @@ def __init__(self, _vehicle_dir: str, vehicle_type: str) -> None: self.configuration_steps_filename = "configuration_steps_" + vehicle_type + ".json" self.configuration_steps: dict[str, dict] = {} self.configuration_phases: dict[str, dict] = {} - self.forced_parameters: dict[str, dict] = {} - self.derived_parameters: dict[str, dict] = {} + self.forced_parameters: dict[str, ParDict] = {} + self.derived_parameters: dict[str, ParDict] = {} self.log_loaded_file = False def re_init(self, vehicle_dir: str, vehicle_type: str) -> None: # pylint: disable=too-many-branches @@ -188,7 +188,7 @@ def compute_parameters(self, filename: str, file_info: dict, parameter_type: str continue if filename not in destination: - destination[filename] = {} + destination[filename] = ParDict() change_reason = _(parameter_info["Change Reason"]) if parameter_info["Change Reason"] else "" destination[filename][parameter] = Par(float(result), change_reason) except (SyntaxError, NameError, KeyError, StopIteration) as _e: diff --git a/ardupilot_methodic_configurator/backend_flightcontroller.py b/ardupilot_methodic_configurator/backend_flightcontroller.py index 4abc86227..5f3725a2f 100644 --- a/ardupilot_methodic_configurator/backend_flightcontroller.py +++ b/ardupilot_methodic_configurator/backend_flightcontroller.py @@ -27,10 +27,10 @@ from serial.serialutil import SerialException from ardupilot_methodic_configurator import _ -from ardupilot_methodic_configurator.annotate_params import Par from ardupilot_methodic_configurator.argparse_check_range import CheckRange from ardupilot_methodic_configurator.backend_flightcontroller_info import BackendFlightcontrollerInfo from ardupilot_methodic_configurator.backend_mavftp import MAVFTP +from ardupilot_methodic_configurator.data_model_par_dict import ParDict # pylint: disable=too-many-lines @@ -73,7 +73,7 @@ class FlightController: # pylint: disable=too-many-public-methods Attributes: device (str): The connection string to the flight controller. master (mavutil.mavlink_connection): The MAVLink connection object. - fc_parameters (Dict[str, float]): A dictionary of flight controller parameters. + fc_parameters (dict[str, float]): A dictionary of flight controller parameters. """ @@ -525,24 +525,24 @@ def __process_autopilot_version(self, m: MAVLink_autopilot_version_message, bann def download_params( self, progress_callback: Union[None, Callable[[int, int], None]] = None - ) -> tuple[dict[str, float], dict[str, "Par"]]: + ) -> tuple[dict[str, float], ParDict]: """ Requests all flight controller parameters from a MAVLink connection. Returns: - Dict[str, float]: A dictionary of flight controller parameters. - Dict[str, Par]: A dictionary of flight controller default parameters. + dict[str, float]: A dictionary of flight controller parameters. + ParDict: A dictionary of flight controller default parameters. """ # FIXME this entire if statement is for testing only, remove it later pylint: disable=fixme if self.master is None and self.comport is not None and self.comport.device == "test": filename = "params.param" logging_warning(_("Testing active, will load all parameters from the %s file"), filename) - par_dict_with_comments = Par.load_param_file_into_dict(filename) - return {k: v.value for k, v in par_dict_with_comments.items()}, {} + par_dict_with_comments = ParDict.from_file(filename) + return {k: v.value for k, v in par_dict_with_comments.items()}, ParDict() if self.master is None: - return {}, {} + return {}, ParDict() # Check if MAVFTP is supported comport_device = getattr(self.comport, "device", "") @@ -554,7 +554,7 @@ def download_params( return param_dict, default_param_dict logging_info(_("MAVFTP is not supported by the %s flight controller, fallback to MAVLink"), comport_device) - return self.__download_params_via_mavlink(progress_callback), {} + return self.__download_params_via_mavlink(progress_callback), ParDict() def __download_params_via_mavlink( self, progress_callback: Union[None, Callable[[int, int], None]] = None @@ -597,9 +597,9 @@ def __download_params_via_mavlink( def download_params_via_mavftp( self, progress_callback: Union[None, Callable[[int, int], None]] = None - ) -> tuple[dict[str, float], dict[str, "Par"]]: + ) -> tuple[dict[str, float], ParDict]: if self.master is None: - return {}, {} + return {}, ParDict() mavftp = MAVFTP(self.master, target_system=self.master.target_system, target_component=self.master.target_component) def get_params_progress_callback(completion: float) -> None: @@ -615,13 +615,13 @@ def get_params_progress_callback(completion: float) -> None: time_sleep(0.3) if ret.error_code == 0: # load the parameters from the file - par_dict = Par.load_param_file_into_dict(complete_param_filename) + par_dict = ParDict.from_file(complete_param_filename) for name, data in par_dict.items(): pdict[name] = data.value - defdict = Par.load_param_file_into_dict(default_param_filename) + defdict = ParDict.from_file(default_param_filename) else: ret.display_message() - defdict = {} + defdict = ParDict() return pdict, defdict diff --git a/ardupilot_methodic_configurator/data_model_ardupilot_parameter.py b/ardupilot_methodic_configurator/data_model_ardupilot_parameter.py index dfefcaefb..a509a8dd1 100644 --- a/ardupilot_methodic_configurator/data_model_ardupilot_parameter.py +++ b/ardupilot_methodic_configurator/data_model_ardupilot_parameter.py @@ -12,8 +12,8 @@ from typing import Any, Optional from ardupilot_methodic_configurator import _ -from ardupilot_methodic_configurator.annotate_params import Par from ardupilot_methodic_configurator.backend_filesystem import is_within_tolerance +from ardupilot_methodic_configurator.data_model_par_dict import Par class ParameterUnchangedError(Exception): diff --git a/ardupilot_methodic_configurator/data_model_configuration_step.py b/ardupilot_methodic_configurator/data_model_configuration_step.py index 909339179..cdce17ffe 100644 --- a/ardupilot_methodic_configurator/data_model_configuration_step.py +++ b/ardupilot_methodic_configurator/data_model_configuration_step.py @@ -17,6 +17,7 @@ from ardupilot_methodic_configurator import _ from ardupilot_methodic_configurator.backend_filesystem import LocalFilesystem from ardupilot_methodic_configurator.data_model_ardupilot_parameter import ArduPilotParameter +from ardupilot_methodic_configurator.data_model_par_dict import ParDict class ConfigurationStepProcessor: @@ -157,8 +158,8 @@ def _create_domain_model_parameters( default_par = self.local_filesystem.param_default_dict.get(param_name, None) # Check if parameter is forced or derived - forced_par = self.local_filesystem.forced_parameters.get(selected_file, {}).get(param_name, None) - derived_par = self.local_filesystem.derived_parameters.get(selected_file, {}).get(param_name, None) + forced_par = self.local_filesystem.forced_parameters.get(selected_file, ParDict()).get(param_name, None) + derived_par = self.local_filesystem.derived_parameters.get(selected_file, ParDict()).get(param_name, None) # Get FC value if available fc_value = fc_parameters.get(param_name) diff --git a/ardupilot_methodic_configurator/data_model_par_dict.py b/ardupilot_methodic_configurator/data_model_par_dict.py new file mode 100644 index 000000000..9736f99b8 --- /dev/null +++ b/ardupilot_methodic_configurator/data_model_par_dict.py @@ -0,0 +1,511 @@ +""" +ArduPilot parameter dictionary data model. + +This module provides the Par class and ParDict class which extends dict[str, Par] +with specialized methods for managing ArduPilot parameters. + +SPDX-FileCopyrightText: 2024-2025 Amilcar do Carmo Lucas + +SPDX-License-Identifier: GPL-3.0-or-later +""" + +import logging +import re +from os import path as os_path +from os import popen as os_popen +from sys import exc_info as sys_exc_info +from types import TracebackType +from typing import Callable, Optional, Union + +from ardupilot_methodic_configurator import _ + +# ArduPilot parameter names start with a capital letter and can have capital letters, numbers and _ +PARAM_NAME_REGEX = r"^[A-Z][A-Z_0-9]*$" +PARAM_NAME_MAX_LEN = 16 + + +class Par: + """ + Represents a parameter with a value and an optional comment. + + Attributes: + value (float): The value of the parameter. + comment (Optional[str]): An optional comment associated with the parameter. + + """ + + def __init__(self, value: float, comment: Optional[str] = None) -> None: + self.value = value + self.comment = comment + + def __eq__(self, other: object) -> bool: + """Equality operation.""" + if isinstance(other, Par): + return self.value == other.value and self.comment == other.comment + return False + + def __hash__(self) -> int: + """Hash operation for using Par objects in sets and as dict keys.""" + return hash((self.value, self.comment)) + + +class ParDict(dict[str, Par]): + """ + A specialized dictionary for managing ArduPilot parameters. + + This class extends dict[str, Par] to provide additional functionality + for merging and comparing parameter dictionaries. + """ + + def __init__(self, initial_data: Optional[dict[str, Par]] = None) -> None: + """ + Initialize the ParDict. + + Args: + initial_data: Optional initial parameter data to populate the dictionary. + + """ + super().__init__() + if initial_data is not None: + self.update(initial_data) + + @staticmethod + def load_param_file_into_dict(param_file: str) -> "ParDict": + """ + Loads an ArduPilot parameter file into a ParDict with name, value pairs. + + Args: + param_file (str): The name of the parameter file to load. + + Returns: + ParDict: A ParDict containing the parameters from the file. + + """ + parameter_dict = ParDict() + try: + with open(param_file, encoding="utf-8") as f_handle: + for i, f_line in enumerate(f_handle, start=1): + original_line = f_line + line = f_line.strip() + comment = None + if not line: + continue # skip empty lines + if line[0] == "#": + continue # skip comments + if "#" in line: + line, comment = line.split("#", 1) # strip trailing comments + comment = comment.strip() + if "," in line: + # parse mission planner style parameter files + parameter, value = line.split(",", 1) + elif " " in line: + # parse mavproxy style parameter files + parameter, value = line.split(" ", 1) + elif "\t" in line: + parameter, value = line.split("\t", 1) + else: + msg = f"Missing parameter-value separator: {line} in {param_file} line {i}" + raise SystemExit(msg) + # Strip whitespace from both parameter name and value immediately after splitting + parameter = parameter.strip() + value = value.strip() + ParDict._validate_parameter(param_file, parameter_dict, i, original_line, comment, parameter, value) + except UnicodeDecodeError as exp: + msg = f"Fatal error reading {param_file}: {exp}" + raise SystemExit(msg) from exp + return parameter_dict + + @staticmethod + def _validate_parameter( # pylint: disable=too-many-arguments, too-many-positional-arguments + param_file: str, + parameter_dict: "ParDict", + i: int, + original_line: str, + comment: Union[None, str], + parameter_name: str, + value: str, + ) -> None: + if len(parameter_name) > PARAM_NAME_MAX_LEN: + msg = f"Too long parameter name: {parameter_name} in {param_file} line {i}" + raise SystemExit(msg) + if not re.match(PARAM_NAME_REGEX, parameter_name): + msg = f"Invalid characters in parameter name {parameter_name} in {param_file} line {i}" + raise SystemExit(msg) + if parameter_name in parameter_dict: + msg = f"Duplicated parameter {parameter_name} in {param_file} line {i}" + raise SystemExit(msg) + try: + fvalue = float(value) + parameter_dict[parameter_name] = Par(fvalue, comment) + except ValueError as exc: + msg = f"Invalid parameter value {value} in {param_file} line {i}" + raise SystemExit(msg) from exc + except OSError as exc: + _exc_type, exc_value, exc_traceback = sys_exc_info() + if isinstance(exc_traceback, TracebackType): + fname = os_path.split(exc_traceback.tb_frame.f_code.co_filename)[1] + logging.critical("in line %s of file %s: %s", exc_traceback.tb_lineno, fname, exc_value) + msg = f"Caused by line {i} of file {param_file}: {original_line}" + raise SystemExit(msg) from exc + + @staticmethod + def missionplanner_sort(item: str) -> tuple[str, ...]: + """ + Sorts a parameter name according to the rules defined in the Mission Planner software. + + Args: + item: The parameter name to sort. + + Returns: + A tuple representing the sorted parameter name. + + """ + parts = item.split("_") # Split the parameter name by underscore + # Compare the parts separately + return tuple(parts) + + def _format_params(self, file_format: str = "missionplanner") -> list[str]: # pylint: disable=too-many-branches + """ + Formats the parameters in this dictionary into a list of strings. + + Each string in the returned list is a formatted representation of a parameter, + consisting of the parameter's name, its value, and optionally its comment. + + Args: + file_format (str): Can be "missionplanner" or "mavproxy" + + Returns: + List[str]: A list of strings, each string representing a parameter + in the format "name,value # comment". + + """ + if file_format == "missionplanner": + sorted_dict = ParDict(dict(sorted(self.items(), key=lambda x: ParDict.missionplanner_sort(x[0])))) + elif file_format == "mavproxy": + sorted_dict = ParDict(dict(sorted(self.items()))) + else: + msg = f"ERROR: Unsupported file format {file_format}" + raise SystemExit(msg) + + formatted_params = [] + if file_format == "missionplanner": + for key, parameter in sorted_dict.items(): + if isinstance(parameter, Par): + if parameter.comment: + formatted_params.append( + f"{key},{format(parameter.value, '.6f').rstrip('0').rstrip('.')} # {parameter.comment}" + ) + else: + formatted_params.append(f"{key},{format(parameter.value, '.6f').rstrip('0').rstrip('.')}") + else: + formatted_params.append(f"{key},{format(parameter, '.6f').rstrip('0').rstrip('.')}") + elif file_format == "mavproxy": + for key, parameter in sorted_dict.items(): + if isinstance(parameter, Par): + if parameter.comment: + formatted_params.append(f"{key:<16} {parameter.value:<8.6f} # {parameter.comment}") + else: + formatted_params.append(f"{key:<16} {parameter.value:<8.6f}") + else: + formatted_params.append(f"{key:<16} {parameter:<8.6f}") + return formatted_params + + def export_to_param( + self, filename_out: str, file_format: str = "missionplanner", content_header: Optional[list[str]] = None + ) -> None: + """ + Export parameters to a parameter file. + + Args: + filename_out: Output filename. + file_format: File format ("missionplanner" or "mavproxy"). + content_header: Optional list of header lines to include at the top of the file. + + """ + formatted_params = self._format_params(file_format) + with open(filename_out, "w", encoding="utf-8") as output_file: + if content_header: + output_file.write("\n".join(content_header) + "\n") + output_file.writelines(line + "\n" for line in formatted_params) + + @staticmethod + def print_out(formatted_params: list[str], name: str) -> None: + """ + Print out the contents of the provided list. + + If the list is too large, print only the ones that fit on the screen and + wait for user input to continue. + + Args: + formatted_params (List[str]): The list of formatted parameters to print. + name (str): A descriptive string for the list contents + + Returns: + None + + """ + if not formatted_params: + return + + rows_str = "100" # number of lines to display before waiting for user input + + # Get the size of the terminal + if __name__ == "__main__": + rows_str, _columns = os_popen("stty size", "r").read().split() # noqa: S605, S607 + + # Convert rows to integer + rows = int(rows_str) - 2 # -2 for the next print and the input line + + # Convert rows + print(f"\n{name} has {len(formatted_params)} parameters:") # noqa: T201 + for i, line in enumerate(formatted_params): + if i % rows == 0 and __name__ == "__main__": + input(f"\n{name} list is long hit enter to continue") + rows_str, _columns = os_popen("stty size", "r").read().split() # noqa: S605, S607 + rows = int(rows_str) - 2 # -2 for the next print and the input line + print(line) # noqa: T201 + + def append(self, other: "ParDict") -> None: + """ + Append parameters from another ParDict. + + Parameters with the same name will be replaced with values from the other dictionary. + + Args: + other: Another ParDict to append from. + + Raises: + TypeError: If other is not an ParDict instance. + + """ + if not isinstance(other, ParDict): + msg = _("Can only append another ParDict instance") + raise TypeError(msg) + + for param_name, param_value in other.items(): + self[param_name] = param_value + + def remove_if_value_is_similar(self, other: "ParDict") -> None: + """ + Remove parameters from this dictionary if their values match those in another dictionary. + + This method compares only parameter values and ignores comments when determining similarity. + Parameters from the current dictionary are removed if they have the same name and value + as parameters in the other dictionary, regardless of comment differences. + + This is particularly useful when comparing flight controller parameters (which have no comments) + with file parameters (which typically have comments). + + Args: + other: Another ParDict to compare against. + + Raises: + TypeError: If other is not an ParDict instance. + + """ + if not isinstance(other, ParDict): + msg = _("Can only compare with another ParDict instance") + raise TypeError(msg) + + # Use the shared filtering logic and replace the contents of the current dictionary + filtered_params = self._get_different_or_missing_params(other) + self.clear() + self.update(filtered_params) + + def get_missing_or_different(self, other: "ParDict") -> "ParDict": + """ + Get parameters that are missing in the other ParDict or have different values. + + Args: + other: The ParDict to compare against. + + Returns: + A new ParDict containing parameters that are missing or different. + + Raises: + TypeError: If other is not an ParDict instance. + + """ + if not isinstance(other, ParDict): + msg = _("Can only compare with another ParDict instance") + raise TypeError(msg) + + # Use the shared filtering logic to create a new ParDict + return ParDict(self._get_different_or_missing_params(other)) + + def _get_different_or_missing_params(self, other: "ParDict") -> dict[str, Par]: + """ + Private helper method to get parameters that are missing or have different values. + + Args: + other: The ParDict to compare against. + + Returns: + A dictionary containing parameters that are missing or different. + + """ + return { + param_name: param_value + for param_name, param_value in self.items() + if param_name not in other or param_value.value != other[param_name].value + } + + @classmethod + def from_file(cls, param_file: str) -> "ParDict": + """ + Create a ParDict by loading from a parameter file. + + Args: + param_file: Path to the parameter file. + + Returns: + A new ParDict loaded from the file. + + """ + param_dict = ParDict.load_param_file_into_dict(param_file) + return cls(param_dict) + + @classmethod + def from_float_dict(cls, param_dict: dict[str, float], default_comment: str = "") -> "ParDict": + """ + Create a ParDict from a dictionary of parameter names to float values. + + Args: + param_dict: Dictionary mapping parameter names to float values. + default_comment: Default comment to apply to all parameters. + + Returns: + A new ParDict with Par objects created from the float values. + + """ + result = cls() + for param_name, param_value in param_dict.items(): + result[param_name] = Par(float(param_value), default_comment) + return result + + @classmethod + def from_fc_parameters(cls, fc_params: dict[str, float]) -> "ParDict": + """ + Create a ParDict from flight controller parameters (dict[str, float]). + + Args: + fc_params: Dictionary of flight controller parameters. + + Returns: + A new ParDict with Par objects created from the flight controller parameters. + + """ + return cls.from_float_dict(fc_params) + + def _filter_by_defaults( + self, default_params: "ParDict", tolerance_func: Optional[Callable[[float, float], bool]] = None + ) -> "ParDict": + """ + Filter out parameters that have default values within tolerance. + + Args: + default_params: ParDict containing default parameter values. + tolerance_func: Function to check if values are within tolerance. + If None, uses exact comparison. + + Returns: + A new ParDict containing only non-default parameters. + + """ + result = ParDict() + for param_name, param_info in self.items(): + if param_name in default_params: + if tolerance_func: + if not tolerance_func(param_info.value, default_params[param_name].value): + result[param_name] = param_info + elif param_info.value != default_params[param_name].value: + result[param_name] = param_info + else: + result[param_name] = param_info + return result + + def _filter_by_readonly(self, doc_dict: dict) -> "ParDict": + """ + Filter parameters that are marked as read-only in the documentation. + + Args: + doc_dict: Documentation dictionary containing parameter metadata. + + Returns: + A new ParDict containing only read-only parameters. + + """ + result = ParDict() + for param_name, param_info in self.items(): + if param_name in doc_dict and doc_dict[param_name].get("ReadOnly", False): + result[param_name] = param_info + return result + + def _filter_by_calibration(self, doc_dict: dict) -> "ParDict": + """ + Filter parameters that are marked as calibration parameters in the documentation. + + Args: + doc_dict: Documentation dictionary containing parameter metadata. + + Returns: + A new ParDict containing only calibration parameters. + + """ + result = ParDict() + for param_name, param_info in self.items(): + if param_name in doc_dict and doc_dict[param_name].get("Calibration", False): + result[param_name] = param_info + return result + + def categorize_by_documentation( + self, + doc_dict: dict, + default_params: "ParDict", + tolerance_func: Optional[Callable[[float, float], bool]] = None, + ) -> tuple["ParDict", "ParDict", "ParDict"]: + """ + Categorize parameters into read-only, calibration, and other non-default parameters. + + Args: + doc_dict: Documentation dictionary containing parameter metadata. + default_params: ParDict containing default parameter values. + tolerance_func: Function to check if values are within tolerance. + + Returns: + A tuple of three ParDict objects: + - Non-default read-only parameters + - Non-default writable calibration parameters + - Non-default writable non-calibration parameters + + """ + non_default_params = self._filter_by_defaults(default_params, tolerance_func) + + # there are protected members from a locally created object, so it is OK to access them like this + read_only_params = non_default_params._filter_by_readonly(doc_dict) # pylint: disable=protected-access # noqa: SLF001 + calibration_params = non_default_params._filter_by_calibration(doc_dict) # pylint: disable=protected-access # noqa: SLF001 + + # Non-calibration parameters are those that are not read-only and not calibration + other_params = ParDict() + for param_name, param_info in non_default_params.items(): + if param_name not in read_only_params and param_name not in calibration_params: + other_params[param_name] = param_info + + return read_only_params, calibration_params, other_params + + def annotate_with_comments(self, comment_lookup: dict[str, str]) -> "ParDict": + """ + Create a new ParDict with comments added from a lookup table. + + Args: + comment_lookup: Dictionary mapping parameter names to their comments. + + Returns: + A new ParDict with updated comments. + + """ + result = ParDict() + for param_name, param in self.items(): + new_comment = comment_lookup.get(param_name, param.comment or "") + result[param_name] = Par(param.value, new_comment) + return result diff --git a/ardupilot_methodic_configurator/frontend_tkinter_flightcontroller_info.py b/ardupilot_methodic_configurator/frontend_tkinter_flightcontroller_info.py index 452e192dd..e2acdeac9 100644 --- a/ardupilot_methodic_configurator/frontend_tkinter_flightcontroller_info.py +++ b/ardupilot_methodic_configurator/frontend_tkinter_flightcontroller_info.py @@ -14,8 +14,8 @@ from typing import Callable, Optional, Union from ardupilot_methodic_configurator import _, __version__ -from ardupilot_methodic_configurator.annotate_params import Par from ardupilot_methodic_configurator.backend_flightcontroller import FlightController +from ardupilot_methodic_configurator.data_model_par_dict import ParDict from ardupilot_methodic_configurator.frontend_tkinter_base_window import BaseWindow from ardupilot_methodic_configurator.frontend_tkinter_progress_window import ProgressWindow @@ -29,7 +29,7 @@ class FlightControllerInfoPresenter: def __init__(self, flight_controller: FlightController) -> None: self.flight_controller = flight_controller - self.param_default_values: dict[str, Par] = {} + self.param_default_values: ParDict = ParDict() def get_info_data(self) -> dict[str, Union[str, dict[str, str]]]: """Get formatted flight controller information for display.""" @@ -39,7 +39,7 @@ def log_flight_controller_info(self) -> None: """Log flight controller information.""" self.flight_controller.info.log_flight_controller_info() - def download_parameters(self, progress_callback: Optional[Callable[[int, int], None]] = None) -> dict[str, Par]: + def download_parameters(self, progress_callback: Optional[Callable[[int, int], None]] = None) -> ParDict: """ Download flight controller parameters. @@ -55,7 +55,7 @@ def download_parameters(self, progress_callback: Optional[Callable[[int, int], N self.param_default_values = param_default_values return param_default_values - def get_param_default_values(self) -> dict[str, Par]: + def get_param_default_values(self) -> ParDict: """Get parameter default values.""" return self.param_default_values @@ -120,6 +120,6 @@ def _download_flight_controller_parameters(self) -> None: param_download_progress_window.destroy() # for the case that '--device test' and there is no real FC connected self.root.destroy() - def get_param_default_values(self) -> dict[str, Par]: + def get_param_default_values(self) -> ParDict: """Get parameter default values from the presenter.""" return self.presenter.get_param_default_values() diff --git a/ardupilot_methodic_configurator/frontend_tkinter_parameter_editor.py b/ardupilot_methodic_configurator/frontend_tkinter_parameter_editor.py index ecc915041..c18dd5eb9 100755 --- a/ardupilot_methodic_configurator/frontend_tkinter_parameter_editor.py +++ b/ardupilot_methodic_configurator/frontend_tkinter_parameter_editor.py @@ -28,12 +28,12 @@ from webbrowser import open as webbrowser_open # to open the blog post documentation from ardupilot_methodic_configurator import _, __version__ -from ardupilot_methodic_configurator.annotate_params import Par from ardupilot_methodic_configurator.backend_filesystem import LocalFilesystem, is_within_tolerance from ardupilot_methodic_configurator.backend_filesystem_program_settings import ProgramSettings from ardupilot_methodic_configurator.backend_flightcontroller import FlightController from ardupilot_methodic_configurator.backend_internet import download_file_from_url from ardupilot_methodic_configurator.common_arguments import add_common_arguments +from ardupilot_methodic_configurator.data_model_par_dict import Par, ParDict from ardupilot_methodic_configurator.frontend_tkinter_autoresize_combobox import AutoResizeCombobox from ardupilot_methodic_configurator.frontend_tkinter_base_window import BaseWindow from ardupilot_methodic_configurator.frontend_tkinter_directory_selection import VehicleDirectorySelectionWidgets @@ -517,7 +517,7 @@ def __should_copy_fc_values_to_file(self, selected_file: str) -> None: # pylint message_label.pack(padx=10, pady=10) # Result variable - result: list[Literal[None, True, False]] = [None] + result: list[Optional[Literal[True, False]]] = [None] # Button frame button_frame = tk.Frame(dialog) @@ -832,8 +832,50 @@ def upload_selected_params(self, selected_params: dict) -> None: self.upload_selected_params(selected_params) else: logging_info(_("All parameters uploaded to the flight controller successfully")) + + # Export FC parameters that are missing or different from AMC parameter files + self._export_fc_params_missing_or_different_in_amc_files() + self.local_filesystem.write_last_uploaded_filename(self.current_file) + def _export_fc_params_missing_or_different_in_amc_files(self) -> None: + """ + Export flight controller parameters that are missing or different in AMC parameter files. + + This function creates a compound state of all parameters from AMC files (excluding defaults), + compares them with FC parameters, and exports any parameters that are either missing from + AMC files or have different values to a separate parameter file. + """ + # Create the compounded state of all parameters stored in the files + compound = ParDict() + default = ParDict() + for file_name, file_params in self.local_filesystem.file_parameters.items(): + if file_name == "00_default.param": + default = ParDict(file_params) + else: + compound.append(ParDict(file_params)) + + # Create FC parameters dictionary + fc_parameters = ParDict.from_fc_parameters(self.flight_controller.fc_parameters) + + # Remove default parameters from FC parameters if default file exists + fc_parameters.remove_if_value_is_similar(default) + + # Calculate parameters that only exist in fc_parameters or have a different value from compound + params_missing_in_the_amc_param_files = fc_parameters.get_missing_or_different(compound) + + # Export to file if there are any missing/different parameters + if params_missing_in_the_amc_param_files: + filename = "fc_params_missing_or_different_in_the_amc_param_files.param" + self.local_filesystem.export_to_param(params_missing_in_the_amc_param_files, filename, annotate_doc=False) + logging_info( + _("Exported %d FC parameters missing or different in AMC files to %s"), + len(params_missing_in_the_amc_param_files), + filename, + ) + else: + logging_info(_("No FC parameters are missing or different from AMC parameter files")) + def _configuration_step_is_optional(self, file_name: str, threshold_pct: int = 20) -> bool: # Check if the configuration step for the given file is optional mandatory_text, _mandatory_url = self.local_filesystem.get_documentation_text_and_url(file_name, "mandatory") @@ -959,7 +1001,7 @@ def write_summary_files(self) -> None: # pylint: disable=too-many-locals ] self.write_zip_file(files_to_zip) - def write_summary_file(self, param_dict: dict, filename: str, annotate_doc: bool) -> bool: + def write_summary_file(self, param_dict: ParDict, filename: str, annotate_doc: bool) -> bool: should_write_file = True if param_dict: if self.local_filesystem.vehicle_configuration_file_exists(filename): diff --git a/ardupilot_methodic_configurator/frontend_tkinter_parameter_editor_table.py b/ardupilot_methodic_configurator/frontend_tkinter_parameter_editor_table.py index c2813a770..378049cc6 100644 --- a/ardupilot_methodic_configurator/frontend_tkinter_parameter_editor_table.py +++ b/ardupilot_methodic_configurator/frontend_tkinter_parameter_editor_table.py @@ -19,7 +19,6 @@ from typing import Union from ardupilot_methodic_configurator import _ -from ardupilot_methodic_configurator.annotate_params import Par from ardupilot_methodic_configurator.backend_filesystem import LocalFilesystem from ardupilot_methodic_configurator.data_model_ardupilot_parameter import ( ArduPilotParameter, @@ -28,6 +27,7 @@ ParameterUnchangedError, ) from ardupilot_methodic_configurator.data_model_configuration_step import ConfigurationStepProcessor +from ardupilot_methodic_configurator.data_model_par_dict import Par, ParDict from ardupilot_methodic_configurator.frontend_tkinter_base_window import BaseWindow from ardupilot_methodic_configurator.frontend_tkinter_entry_dynamic import EntryWithDynamicalyFilteredListbox from ardupilot_methodic_configurator.frontend_tkinter_pair_tuple_combobox import ( @@ -828,14 +828,14 @@ def _confirm_parameter_addition(self, param_name: str, fc_parameters: dict[str, ) return False - def get_upload_selected_params(self, current_file: str, gui_complexity: str) -> dict[str, Par]: + def get_upload_selected_params(self, current_file: str, gui_complexity: str) -> ParDict: """Get the parameters selected for upload.""" # Check if we should show upload column based on GUI complexity if not self._should_show_upload_column(gui_complexity): # all parameters are selected for upload in simple mode return self.local_filesystem.file_parameters[current_file] - selected_params = {} + selected_params = ParDict() for param_name, checkbutton_state in self.upload_checkbutton_var.items(): if checkbutton_state.get(): selected_params[param_name] = self.local_filesystem.file_parameters[current_file][param_name] diff --git a/ardupilot_methodic_configurator/param_pid_adjustment_update.py b/ardupilot_methodic_configurator/param_pid_adjustment_update.py index 20fdd7749..4e179a34a 100755 --- a/ardupilot_methodic_configurator/param_pid_adjustment_update.py +++ b/ardupilot_methodic_configurator/param_pid_adjustment_update.py @@ -17,15 +17,14 @@ import argparse import os import re -import subprocess -from typing import Callable, Optional, Union +from typing import Callable, Union import argcomplete from argcomplete.completers import DirectoriesCompleter, FilesCompleter -PARAM_NAME_REGEX = r"^[A-Z][A-Z_0-9]*$" -PARAM_NAME_MAX_LEN = 16 -VERSION = "1.0" +from ardupilot_methodic_configurator.data_model_par_dict import PARAM_NAME_MAX_LEN, PARAM_NAME_REGEX, Par, ParDict + +VERSION = "1.1" def create_argument_parser() -> argparse.ArgumentParser: @@ -52,9 +51,9 @@ def create_argument_parser() -> argparse.ArgumentParser: parser.add_argument( "-a", "--adjustment_factor", - type=ranged_type(float, 0.1, 0.8), + type=ranged_type(float, 0.1, 1.2), default=0.5, - help="The adjustment factor to apply to the optimized parameters. Must be in the interval 0.1 to 0.8. Default is 0.5.", + help="The adjustment factor to apply to the optimized parameters. Must be in the interval 0.1 to 1.2. Default is 0.5.", ) parser.add_argument( "-v", @@ -98,77 +97,65 @@ def range_checker(arg: str) -> Union[int, float]: return range_checker -class Par: +def load_param_file_with_content(param_file: str) -> tuple[ParDict, list[str]]: """ - A class representing a parameter with a value and an optional comment. + Load parameter file into ParDict and return the file content as well. - Attributes: - value (float): The value of the parameter. - comment (str): An optional comment describing the parameter. + This is a helper function that extends ParDict.load_param_file_into_dict() + to also return the original file content lines for header preservation. - """ + Args: + param_file: Path to the parameter file. - def __init__(self, value: float, comment: Optional[str] = None) -> None: - self.value = value - self.comment = comment - - @staticmethod - def load_param_file_into_dict(param_file: str) -> tuple[dict[str, "Par"], list[str]]: - parameter_dict = {} - content = [] - with open(param_file, encoding="utf-8") as f_handle: - for n, f_line in enumerate(f_handle, start=1): - line = f_line.strip() - content.append(line) - comment = None - if not line or line.startswith("#"): - continue - if "#" in line: - line, comment = line.split("#", 1) - comment = comment.strip() - if "," in line: - parameter, value = line.split(",", 1) - elif " " in line: - parameter, value = line.split(" ", 1) - elif "\t" in line: - parameter, value = line.split("\t", 1) - else: - msg = f"Missing parameter-value separator: {line} in {param_file} line {n}" - raise SystemExit(msg) - if len(parameter) > PARAM_NAME_MAX_LEN: - msg = f"Too long parameter name: {parameter} in {param_file} line {n}" - raise SystemExit(msg) - if not re.match(PARAM_NAME_REGEX, parameter): - msg = f"Invalid characters in parameter name {parameter} in {param_file} line {n}" - raise SystemExit(msg) - try: - fvalue = float(value) - except ValueError as exc: - msg = f"Invalid parameter value {value} in {param_file} line {n}" - raise SystemExit(msg) from exc - if parameter in parameter_dict: - msg = f"Duplicated parameter {parameter} in {param_file} line {n}" - raise SystemExit(msg) - parameter_dict[parameter] = Par(fvalue, comment) - return parameter_dict, content - - @staticmethod - def export_to_param(param_dict: dict[str, "Par"], filename_out: str, content_header: Optional[list[str]] = None) -> None: - if content_header is None: - content_header = [] - with open(filename_out, "w", encoding="utf-8") as output_file: - if content_header: - output_file.write("\n".join(content_header) + "\n") - for key, par in param_dict.items(): - line = f"{key},{format(par.value, '.6f').rstrip('0').rstrip('.')}" - if par.comment: - line += f" # {par.comment}" - output_file.write(line + "\n") + Returns: + A tuple of (ParDict, list of file content lines). + + """ + parameter_dict = ParDict() + content = [] + with open(param_file, encoding="utf-8") as f_handle: + for n, f_line in enumerate(f_handle, start=1): + line = f_line.strip() + content.append(line) + comment = None + if not line or line.startswith("#"): + continue + if "#" in line: + line, comment = line.split("#", 1) + comment = comment.strip() + if "," in line: + parameter, value = line.split(",", 1) + elif " " in line: + parameter, value = line.split(" ", 1) + elif "\t" in line: + parameter, value = line.split("\t", 1) + else: + msg = f"Missing parameter-value separator: {line} in {param_file} line {n}" + raise SystemExit(msg) + # Strip whitespace from both parameter name and value immediately after splitting + parameter = parameter.strip() + value = value.strip() + if len(parameter) > PARAM_NAME_MAX_LEN: + msg = f"Too long parameter name: {parameter} in {param_file} line {n}" + raise SystemExit(msg) + if not re.match(PARAM_NAME_REGEX, parameter): + msg = f"Invalid characters in parameter name {parameter} in {param_file} line {n}" + raise SystemExit(msg) + try: + fvalue = float(value) + except ValueError as exc: + msg = f"Invalid parameter value {value} in {param_file} line {n}" + raise SystemExit(msg) from exc + if parameter in parameter_dict: + msg = f"Duplicated parameter {parameter} in {param_file} line {n}" + raise SystemExit(msg) + parameter_dict[parameter] = Par(fvalue, comment) + return parameter_dict, content def update_pid_adjustment_params( directory: str, optimized_param_file: str, adjustment_factor: float -) -> tuple[dict[str, "Par"], str, list[str]]: +) -> tuple[ParDict, str, list[str]]: """ Updates the PID adjustment parameters values based on the given adjustment factor. @@ -189,13 +176,13 @@ def update_pid_adjustment_params( pid_adjustment_file_path = os.path.join(directory, "16_pid_adjustment.param") # Load the default parameter file into a dictionary (comment source) - default_params_dict, _ = Par.load_param_file_into_dict(default_param_file_path) + default_params_dict = ParDict.from_file(default_param_file_path) # Load the optimized parameter file into a dictionary (source) - optimized_params_dict, _ = Par.load_param_file_into_dict(optimized_param_file_path) + optimized_params_dict = ParDict.from_file(optimized_param_file_path) # Load the PID adjustment parameter file into a dictionary (destination) - pid_adjustment_params_dict, content = Par.load_param_file_into_dict(pid_adjustment_file_path) + pid_adjustment_params_dict, content = load_param_file_with_content(pid_adjustment_file_path) if not default_params_dict: msg = f"Failed to load default parameters from {default_param_file_path}" @@ -240,9 +227,7 @@ def main() -> None: args.directory, args.optimized_param_file, args.adjustment_factor ) # export the updated PID adjust parameters to a file, preserving the first eight header lines - Par.export_to_param(pid_adjustment_params_dict, pid_adjustment_file_path, content_header) - # annotate each parameter with up-to date documentation - subprocess.run(["./annotate_params.py", os.path.join(args.directory, "16_pid_adjustment.param")], check=True) # noqa: S603 + pid_adjustment_params_dict.export_to_param(pid_adjustment_file_path, content_header=content_header) if __name__ == "__main__": diff --git a/tests/test_annotate_params.py b/tests/test_annotate_params.py index 288f5f59f..3391ee31a 100755 --- a/tests/test_annotate_params.py +++ b/tests/test_annotate_params.py @@ -27,7 +27,6 @@ from ardupilot_methodic_configurator.annotate_params import ( BASE_URL, PARAM_DEFINITION_XML_FILE, - Par, create_doc_dict, extract_parameter_name_and_validate, format_columns, @@ -42,8 +41,9 @@ split_into_lines, update_parameter_documentation, ) +from ardupilot_methodic_configurator.data_model_par_dict import Par, ParDict -# pylint: disable=too-many-lines +# pylint: disable=too-many-lines, protected-access @pytest.fixture @@ -98,7 +98,7 @@ def setUp(self) -> None: @patch("builtins.open", new_callable=mock.mock_open, read_data="") @patch("os.path.isfile") - @patch("ardupilot_methodic_configurator.annotate_params.Par.load_param_file_into_dict") + @patch("ardupilot_methodic_configurator.data_model_par_dict.ParDict.load_param_file_into_dict") def test_get_xml_data_local_file(self, mock_load_param, mock_isfile, mock_open_) -> None: # Mock the isfile function to return True mock_isfile.return_value = True @@ -135,7 +135,7 @@ def test_get_xml_data_remote_file(self, mock_get) -> None: mock_get.assert_called_once_with("http://example.com/test.xml", timeout=5) @patch("os.path.isfile") - @patch("ardupilot_methodic_configurator.annotate_params.Par.load_param_file_into_dict") + @patch("ardupilot_methodic_configurator.data_model_par_dict.ParDict.load_param_file_into_dict") def test_get_xml_data_script_dir_file(self, mock_load_param, mock_isfile) -> None: # Mock the isfile function to return False for the current directory and True for the script directory def side_effect(_filename) -> bool: @@ -527,7 +527,7 @@ def test_print_read_only_params(self, mock_info) -> None: mock_info.assert_has_calls([mock.call("ReadOnly parameters:"), mock.call("PARAM1")]) def test_update_parameter_documentation_invalid_target(self) -> None: - with pytest.raises(ValueError, match="Target 'invalid_target' is neither a file nor a directory."): + with pytest.raises(ValueError, match=r"Target 'invalid_target' is neither a file nor a directory\."): update_parameter_documentation(self.doc_dict, "invalid_target") def test_invalid_parameter_name(self) -> None: @@ -587,7 +587,7 @@ def test_get_xml_url_valid_vehicles(self) -> None: def test_get_xml_url_invalid_vehicle(self) -> None: """Test get_xml_url with invalid vehicle type.""" - with pytest.raises(ValueError, match="Vehicle type 'InvalidVehicle' is not supported."): + with pytest.raises(ValueError, match=r"Vehicle type 'InvalidVehicle' is not supported\."): get_xml_url("InvalidVehicle", "4.3") def test_split_into_lines_edge_cases(self) -> None: @@ -714,26 +714,26 @@ def test_par_class_methods(self) -> None: tf.flush() with pytest.raises(SystemExit): - Par.load_param_file_into_dict(tf.name) + ParDict.load_param_file_into_dict(tf.name) def test_format_params_methods(self) -> None: - """Test Par.format_params method.""" - param_dict = {"PARAM1": Par(100.0, "comment1"), "PARAM2": Par(200.0), "PARAM3": 300.0} + """Test ParDict._format_params method.""" + param_dict = ParDict({"PARAM1": Par(100.0, "comment1"), "PARAM2": Par(200.0), "PARAM3": Par(300.0)}) # Test MissionPlanner format - mp_format = Par.format_params(param_dict, "missionplanner") + mp_format = param_dict._format_params("missionplanner") assert any("PARAM1,100" in line for line in mp_format) assert any("# comment1" in line for line in mp_format) # Test MAVProxy format - mavproxy_format = Par.format_params(param_dict, "mavproxy") + mavproxy_format = param_dict._format_params("mavproxy") # Use correct spacing format - 16 chars for name, 8 for value assert any("PARAM1 100.000000" in line for line in mavproxy_format) assert any("# comment1" in line for line in mavproxy_format) # Test invalid format with pytest.raises(SystemExit): - Par.format_params(param_dict, "invalid_format") + param_dict._format_params("invalid_format") class AnnotateParamsTest(unittest.TestCase): @@ -809,7 +809,7 @@ def test_main_oserror(self, mock_file) -> None: @patch("ardupilot_methodic_configurator.annotate_params.get_xml_url") def test_get_xml_url_exception(self, mock_get_xml_url_) -> None: mock_get_xml_url_.side_effect = ValueError("Mocked Value Error") - with pytest.raises(ValueError, match="Vehicle type 'NonExistingVehicle' is not supported."): # noqa: PT012 + with pytest.raises(ValueError, match=r"Vehicle type 'NonExistingVehicle' is not supported\."): # noqa: PT012 get_xml_url("NonExistingVehicle", "4.0") @patch("requests.get") @@ -942,7 +942,7 @@ def test_par_class_methods_comprehensive(self) -> None: tf.write("\n") # empty line tf_name = tf.name - param_dict = Par.load_param_file_into_dict(tf_name) + param_dict = ParDict.load_param_file_into_dict(tf_name) os.unlink(tf_name) assert len(param_dict) == 3 @@ -960,7 +960,7 @@ def test_par_class_methods_comprehensive(self) -> None: tf_name = tf.name with pytest.raises(SystemExit): - Par.load_param_file_into_dict(tf_name) + ParDict.load_param_file_into_dict(tf_name) os.unlink(tf_name) def test_missionplanner_sort_function(self) -> None: diff --git a/tests/test_backend_filesystem.py b/tests/test_backend_filesystem.py index 591b1989e..e77299d12 100755 --- a/tests/test_backend_filesystem.py +++ b/tests/test_backend_filesystem.py @@ -16,8 +16,8 @@ from subprocess import SubprocessError from unittest.mock import MagicMock, mock_open, patch -from ardupilot_methodic_configurator.annotate_params import Par from ardupilot_methodic_configurator.backend_filesystem import LocalFilesystem, is_within_tolerance +from ardupilot_methodic_configurator.data_model_par_dict import Par, ParDict # pylint: disable=too-many-lines, too-many-arguments, too-many-positional-arguments @@ -43,15 +43,18 @@ def test_read_params_from_files(self) -> None: ), patch("ardupilot_methodic_configurator.backend_filesystem.os_path.isdir", return_value=True), patch( - "ardupilot_methodic_configurator.backend_filesystem.Par.load_param_file_into_dict", - return_value={"PARAM1": 1.0}, + "ardupilot_methodic_configurator.backend_filesystem.ParDict.load_param_file_into_dict", + return_value=ParDict({"PARAM1": Par(1.0)}), ), patch("ardupilot_methodic_configurator.backend_filesystem.os_path.join", side_effect=os_path.join), ): result = filesystem.read_params_from_files() assert len(result) == 1 assert "02_test.param" in result - assert result["02_test.param"] == {"PARAM1": 1.0} + # Compare ParDict object - check it has the expected parameter + assert isinstance(result["02_test.param"], ParDict) + assert "PARAM1" in result["02_test.param"] + assert result["02_test.param"]["PARAM1"].value == 1.0 def test_str_to_bool(self) -> None: lfs = LocalFilesystem( @@ -647,7 +650,7 @@ def test_categorize_parameters(self) -> None: lfs.param_default_dict = {"PARAM1": MagicMock(value=1.0)} lfs.doc_dict = {"PARAM1": {"ReadOnly": True}, "PARAM2": {"Calibration": True}, "PARAM3": {}} - test_params = {"PARAM1": MagicMock(value=2.0), "PARAM2": MagicMock(value=2.0), "PARAM3": MagicMock(value=2.0)} + test_params = ParDict({"PARAM1": Par(2.0), "PARAM2": Par(2.0), "PARAM3": Par(2.0)}) readonly, calibration, other = lfs.categorize_parameters(test_params) @@ -671,12 +674,14 @@ def test_update_and_export_vehicle_params_from_fc(self) -> None: param2_mock = MagicMock() param2_mock.value = 0.0 - lfs.file_parameters = {"test.param": {"PARAM1": param1_mock, "PARAM2": param2_mock}} + # Create a ParDict instead of a regular dict + param_dict = ParDict({"PARAM1": param1_mock, "PARAM2": param2_mock}) + lfs.file_parameters = {"test.param": param_dict} lfs.configuration_steps = {"test.param": {"forced": {}, "derived": {}}} with ( - patch("ardupilot_methodic_configurator.backend_filesystem.Par.export_to_param") as mock_export, - patch("ardupilot_methodic_configurator.backend_filesystem.Par.format_params") as mock_format, + patch.object(param_dict, "export_to_param") as mock_export, + patch("ardupilot_methodic_configurator.backend_filesystem.ParDict._format_params") as mock_format, ): mock_format.return_value = "formatted_params" @@ -684,7 +689,7 @@ def test_update_and_export_vehicle_params_from_fc(self) -> None: assert result == "" assert param1_mock.value == 1.0 assert param2_mock.value == 2.0 - mock_export.assert_called_once_with("formatted_params", os_path.join("vehicle_dir", "test.param")) + mock_export.assert_called_once_with(os_path.join("vehicle_dir", "test.param")) def test_write_param_default_values_to_file(self) -> None: lfs = LocalFilesystem( @@ -692,19 +697,16 @@ def test_write_param_default_values_to_file(self) -> None: ) param_mock = MagicMock() param_mock.value = 1.0 - param_default_values = {"PARAM1": param_mock} + # Create a ParDict instead of a regular dict + param_default_values = ParDict({"PARAM1": param_mock}) with ( - patch("ardupilot_methodic_configurator.backend_filesystem.Par.export_to_param") as mock_export, - patch("ardupilot_methodic_configurator.backend_filesystem.Par.format_params") as mock_format, + patch("ardupilot_methodic_configurator.backend_filesystem.ParDict.export_to_param") as mock_export, ): - mock_format.return_value = "formatted_params" - # Test with new values lfs.write_param_default_values_to_file(param_default_values) assert lfs.param_default_dict == param_default_values - mock_format.assert_called_with(param_default_values) - mock_export.assert_called_with("formatted_params", os_path.join("vehicle_dir", "00_default.param")) + mock_export.assert_called_with(os_path.join("vehicle_dir", "00_default.param")) # Test with same values (no change) mock_export.reset_mock() @@ -717,26 +719,22 @@ def test_export_to_param(self) -> None: ) param_mock = MagicMock() param_mock.value = 1.0 - test_params = {"PARAM1": param_mock} + test_params = ParDict({"PARAM1": param_mock}) with ( - patch("ardupilot_methodic_configurator.backend_filesystem.Par.export_to_param") as mock_export, + patch.object(test_params, "export_to_param") as mock_export, patch("ardupilot_methodic_configurator.backend_filesystem.update_parameter_documentation") as mock_update, - patch("ardupilot_methodic_configurator.backend_filesystem.Par.format_params") as mock_format, ): - mock_format.return_value = "formatted_params" - # Test with documentation annotation lfs.export_to_param(test_params, "test.param", annotate_doc=True) - mock_format.assert_called_with(test_params) - mock_export.assert_called_with("formatted_params", os_path.join("vehicle_dir", "test.param")) + mock_export.assert_called_with(os_path.join("vehicle_dir", "test.param")) mock_update.assert_called_once() # Test without documentation annotation mock_export.reset_mock() mock_update.reset_mock() lfs.export_to_param(test_params, "test.param", annotate_doc=False) - mock_export.assert_called_once() + mock_export.assert_called_with(os_path.join("vehicle_dir", "test.param")) mock_update.assert_not_called() def test_all_intermediate_parameter_file_comments(self) -> None: @@ -895,8 +893,8 @@ def test_backup_fc_parameters_to_file(self) -> None: with ( patch.object(lfs, "vehicle_configuration_file_exists", return_value=False), patch.object(lfs, "_LocalFilesystem__read_last_uploaded_filename", return_value=""), - patch("ardupilot_methodic_configurator.backend_filesystem.Par.export_to_param") as mock_export, - patch("ardupilot_methodic_configurator.backend_filesystem.Par.format_params") as mock_format, + patch("ardupilot_methodic_configurator.backend_filesystem.ParDict.export_to_param") as mock_export, + patch("ardupilot_methodic_configurator.backend_filesystem.ParDict._format_params") as mock_format, ): mock_format.return_value = "formatted_params" lfs.backup_fc_parameters_to_file(test_params, "backup.param") @@ -906,7 +904,7 @@ def test_backup_fc_parameters_to_file(self) -> None: with ( patch.object(lfs, "vehicle_configuration_file_exists", return_value=True), patch.object(lfs, "_LocalFilesystem__read_last_uploaded_filename", return_value=""), - patch("ardupilot_methodic_configurator.backend_filesystem.Par.export_to_param") as mock_export, + patch("ardupilot_methodic_configurator.backend_filesystem.ParDict.export_to_param") as mock_export, ): lfs.backup_fc_parameters_to_file(test_params, "backup.param") mock_export.assert_not_called() @@ -915,8 +913,8 @@ def test_backup_fc_parameters_to_file(self) -> None: with ( patch.object(lfs, "vehicle_configuration_file_exists", return_value=True), patch.object(lfs, "_LocalFilesystem__read_last_uploaded_filename", return_value=""), - patch("ardupilot_methodic_configurator.backend_filesystem.Par.export_to_param") as mock_export, - patch("ardupilot_methodic_configurator.backend_filesystem.Par.format_params") as mock_format, + patch("ardupilot_methodic_configurator.backend_filesystem.ParDict.export_to_param") as mock_export, + patch("ardupilot_methodic_configurator.backend_filesystem.ParDict._format_params") as mock_format, ): mock_format.return_value = "formatted_params" lfs.backup_fc_parameters_to_file(test_params, "backup.param", overwrite_existing_file=True) @@ -926,7 +924,7 @@ def test_backup_fc_parameters_to_file(self) -> None: with ( patch.object(lfs, "vehicle_configuration_file_exists", return_value=False), patch.object(lfs, "_LocalFilesystem__read_last_uploaded_filename", return_value="last_file.param"), - patch("ardupilot_methodic_configurator.backend_filesystem.Par.export_to_param") as mock_export, + patch("ardupilot_methodic_configurator.backend_filesystem.ParDict.export_to_param") as mock_export, ): lfs.backup_fc_parameters_to_file(test_params, "backup.param", even_if_last_uploaded_filename_exists=False) mock_export.assert_not_called() diff --git a/tests/test_backend_filesystem_program_settings.py b/tests/test_backend_filesystem_program_settings.py index 7fe79cc56..ab981eae2 100755 --- a/tests/test_backend_filesystem_program_settings.py +++ b/tests/test_backend_filesystem_program_settings.py @@ -320,7 +320,7 @@ def test_user_gets_error_when_site_config_directory_missing(self) -> None: return_value="/missing/site/config", ), patch("os.path.exists", return_value=False), - pytest.raises(FileNotFoundError, match="site configuration directory.*does not exist"), + pytest.raises(FileNotFoundError, match=r"site configuration directory.*does not exist"), ): # Act: Attempt to access missing site configuration directory ProgramSettings._site_config_dir() @@ -341,7 +341,7 @@ def test_user_gets_error_when_site_config_path_is_not_directory(self) -> None: ), patch("os.path.exists", return_value=True), patch("os.path.isdir", return_value=False), - pytest.raises(NotADirectoryError, match="path.*is not a directory"), + pytest.raises(NotADirectoryError, match=r"path.*is not a directory"), ): # Act: Attempt to access site configuration file as directory ProgramSettings._site_config_dir() diff --git a/tests/test_backend_flightcontroller.py b/tests/test_backend_flightcontroller.py index dc427eee2..148d96b81 100755 --- a/tests/test_backend_flightcontroller.py +++ b/tests/test_backend_flightcontroller.py @@ -16,8 +16,8 @@ import pytest from pymavlink import mavutil -from ardupilot_methodic_configurator.annotate_params import Par from ardupilot_methodic_configurator.backend_flightcontroller import FlightController +from ardupilot_methodic_configurator.data_model_par_dict import Par, ParDict def test_add_connection() -> None: @@ -48,8 +48,8 @@ def test_disconnect() -> None: @patch("builtins.open", new_callable=mock_open, read_data="param1=1\nparam2=2") @patch( - "ardupilot_methodic_configurator.annotate_params.Par.load_param_file_into_dict", - side_effect=lambda x: {"param1": Par(1, x), "param2": Par(2, x)}, + "ardupilot_methodic_configurator.data_model_par_dict.ParDict.load_param_file_into_dict", + side_effect=lambda x: ParDict({"param1": Par(1, x), "param2": Par(2, x)}), ) def test_download_params(mock_load_param_file_into_dict, mock_file) -> None: fc = FlightController(reboot_time=7, baudrate=115200) @@ -63,8 +63,8 @@ def test_download_params(mock_load_param_file_into_dict, mock_file) -> None: @patch("builtins.open", new_callable=mock_open, read_data="param1,1\nparam2,2") @patch( - "ardupilot_methodic_configurator.annotate_params.Par.load_param_file_into_dict", - side_effect=lambda x: {"param1": Par(1, x), "param2": Par(2, x)}, + "ardupilot_methodic_configurator.data_model_par_dict.ParDict.load_param_file_into_dict", + side_effect=lambda x: ParDict({"param1": Par(1, x), "param2": Par(2, x)}), ) def test_set_param(mock_load_param_file_into_dict, mock_file) -> None: fc = FlightController(reboot_time=7, baudrate=115200) @@ -100,8 +100,8 @@ def test_get_connection_tuples() -> None: @patch("builtins.open", new_callable=mock_open, read_data="param1,1\nparam2,2") @patch( - "ardupilot_methodic_configurator.annotate_params.Par.load_param_file_into_dict", - side_effect=lambda x: {"param1": Par(1, x), "param2": Par(2, x)}, + "ardupilot_methodic_configurator.data_model_par_dict.ParDict.load_param_file_into_dict", + side_effect=lambda x: ParDict({"param1": Par(1, x), "param2": Par(2, x)}), ) def test_set_param_and_verify(mock_load_param_file_into_dict, mock_file) -> None: fc = FlightController(reboot_time=7, baudrate=115200) diff --git a/tests/test_data_model_ardupilot_parameter.py b/tests/test_data_model_ardupilot_parameter.py index a68f9b4a7..4b3fc6701 100755 --- a/tests/test_data_model_ardupilot_parameter.py +++ b/tests/test_data_model_ardupilot_parameter.py @@ -14,11 +14,11 @@ import pytest -from ardupilot_methodic_configurator.annotate_params import Par from ardupilot_methodic_configurator.data_model_ardupilot_parameter import ( ArduPilotParameter, ParameterUnchangedError, ) +from ardupilot_methodic_configurator.data_model_par_dict import Par # pylint: disable=redefined-outer-name, protected-access diff --git a/tests/test_data_model_configuration_step.py b/tests/test_data_model_configuration_step.py index b12fc9863..a8880e04a 100755 --- a/tests/test_data_model_configuration_step.py +++ b/tests/test_data_model_configuration_step.py @@ -15,9 +15,9 @@ import pytest -from ardupilot_methodic_configurator.annotate_params import Par from ardupilot_methodic_configurator.data_model_ardupilot_parameter import ArduPilotParameter from ardupilot_methodic_configurator.data_model_configuration_step import ConfigurationStepProcessor +from ardupilot_methodic_configurator.data_model_par_dict import Par # pylint: disable=redefined-outer-name, protected-access diff --git a/tests/test_data_model_par_dict.py b/tests/test_data_model_par_dict.py new file mode 100755 index 000000000..295dd101a --- /dev/null +++ b/tests/test_data_model_par_dict.py @@ -0,0 +1,1275 @@ +#!/usr/bin/env python3 + +""" +Behavior-driven tests for ArduPilot parameter dictionary data model. + +This module contains comprehensive tests for the ParDict class, +focusing on user workflows and business value rather than implementation details. + +SPDX-FileCopyrightText: 2024-2025 Amilcar do Carmo Lucas + +SPDX-License-Identifier: GPL-3.0-or-later +""" + +import os +import tempfile +from collections.abc import Generator +from unittest.mock import patch + +import pytest + +from ardupilot_methodic_configurator.data_model_par_dict import Par, ParDict + +# pylint: disable=redefined-outer-name, too-many-lines + + +@pytest.fixture +def sample_par_objects() -> dict[str, Par]: + """Fixture providing realistic Par objects for testing.""" + return { + "ACRO_YAW_P": Par(4.5, "Yaw P gain"), + "PILOT_SPEED_UP": Par(250.0, "Pilot controlled climb rate"), + "BATT_CAPACITY": Par(5000.0, "Battery capacity in mAh"), + "GPS_TYPE": Par(1.0, "GPS type"), + "COMPASS_ENABLE": Par(1.0, "Enable compass"), + } + + +@pytest.fixture +def parameter_dict(sample_par_objects) -> ParDict: + """Fixture providing a configured ParDict for behavior testing.""" + return ParDict(sample_par_objects) + + +@pytest.fixture +def empty_parameter_dict() -> ParDict: + """Fixture providing an empty ParDict.""" + return ParDict() + + +@pytest.fixture +def alternate_parameter_dict() -> ParDict: + """Fixture providing an alternate parameter dictionary for comparison testing.""" + alternate_data = { + "ACRO_YAW_P": Par(6.0, "Modified Yaw P gain"), # Different value + "NEW_PARAM": Par(100.0, "New parameter"), # New parameter + "COMPASS_ENABLE": Par(1.0, "Enable compass"), # Same value + } + return ParDict(alternate_data) + + +@pytest.fixture +def default_parameters() -> ParDict: + """Fixture providing default parameter values for comparison testing.""" + default_data = { + "ACRO_YAW_P": Par(4.5, "Default yaw P gain"), # Same as sample + "PILOT_SPEED_UP": Par(200.0, "Default climb rate"), # Different from sample + "DEFAULT_ONLY": Par(0.0, "Parameter only in defaults"), + } + return ParDict(default_data) + + +@pytest.fixture +def documentation_dict() -> dict: + """Fixture providing parameter documentation metadata.""" + return { + "ACRO_YAW_P": {"ReadOnly": False, "Calibration": False}, + "PILOT_SPEED_UP": {"ReadOnly": True, "Calibration": False}, + "BATT_CAPACITY": {"ReadOnly": False, "Calibration": True}, + "GPS_TYPE": {"ReadOnly": False, "Calibration": False}, + "COMPASS_ENABLE": {"ReadOnly": False, "Calibration": True}, + } + + +@pytest.fixture +def temp_param_file() -> Generator[str, None, None]: + """Fixture providing a temporary parameter file for testing.""" + content = """# Test parameter file +ACRO_YAW_P,4.5 # Yaw P gain +PILOT_SPEED_UP,250.0 # Pilot controlled climb rate +BATT_CAPACITY,5000.0 # Battery capacity in mAh +GPS_TYPE,1.0 +COMPASS_ENABLE,1.0 # Enable compass +""" + with tempfile.NamedTemporaryFile(mode="w", suffix=".param", delete=False) as f: + f.write(content) + f.flush() + yield f.name + os.unlink(f.name) + + +@pytest.fixture +def temp_mavproxy_file() -> Generator[str, None, None]: + """Fixture providing a temporary MAVProxy-style parameter file.""" + content = """# MAVProxy style parameter file +ACRO_YAW_P 4.500000 # Yaw P gain +PILOT_SPEED_UP 250.000000 # Pilot controlled climb rate +BATT_CAPACITY 5000.000000 +""" + with tempfile.NamedTemporaryFile(mode="w", suffix=".param", delete=False) as f: + f.write(content) + f.flush() + yield f.name + os.unlink(f.name) + + +class TestParClassBehavior: + """Test Par class behavior and functionality.""" + + def test_user_can_create_parameter_with_value_and_comment(self) -> None: + """ + User can create a parameter with both value and comment. + + GIVEN: A user needs to define a parameter with documentation + WHEN: They create a Par object with value and comment + THEN: Both value and comment should be stored correctly + """ + # Arrange & Act: Create parameter with value and comment + param = Par(4.5, "Yaw P gain") + + # Assert: Parameter stores both value and comment + assert param.value == 4.5 + assert param.comment == "Yaw P gain" + + def test_user_can_create_parameter_with_only_value(self) -> None: + """ + User can create a parameter with only a value (no comment). + + GIVEN: A user has a parameter value without documentation + WHEN: They create a Par object with only a value + THEN: The value should be stored and comment should be None + """ + # Arrange & Act: Create parameter with only value + param = Par(250.0) + + # Assert: Parameter stores value with None comment + assert param.value == 250.0 + assert param.comment is None + + def test_user_can_compare_parameters_for_equality(self) -> None: + """ + User can compare parameters to check if they are identical. + + GIVEN: A user has multiple parameter objects + WHEN: They compare parameters with same values and comments + THEN: Parameters should be considered equal + """ + # Arrange: Create identical parameters + param1 = Par(4.5, "Yaw P gain") + param2 = Par(4.5, "Yaw P gain") + param3 = Par(4.5, "Different comment") + + # Act & Assert: Test equality comparisons + assert param1 == param2 # Same value and comment + assert param1 != param3 # Same value, different comment + assert param1 != "not a parameter" # Different type + + def test_user_can_use_parameters_in_sets_and_as_dict_keys(self) -> None: + """ + User can use Par objects in sets and as dictionary keys. + + GIVEN: A user wants to use parameters in advanced data structures + WHEN: They use Par objects in sets or as dictionary keys + THEN: The objects should work correctly due to hash implementation + """ + # Arrange: Create parameters + param1 = Par(4.5, "Yaw P gain") + param2 = Par(4.5, "Yaw P gain") # Same as param1 + param3 = Par(6.0, "Different value") + + # Act: Use parameters in set and as dict keys + param_set = {param1, param2, param3} + param_mapping = {param1: "first", param3: "second"} + + # Assert: Parameters work in advanced data structures + assert len(param_set) == 2 # param1 and param2 are the same + assert param_mapping[param2] == "first" # param2 can access param1's value + + +class TestParDictInitialization: + """Test ParDict initialization workflows.""" + + def test_user_can_create_empty_parameter_dictionary(self) -> None: + """ + User can create an empty parameter dictionary for fresh configurations. + + GIVEN: A user needs to start with a clean parameter configuration + WHEN: They create a new ParDict without initial data + THEN: An empty dictionary should be created successfully + """ + # Arrange & Act: Create empty parameter dictionary + param_dict = ParDict() + + # Assert: Dictionary is empty and functional + assert len(param_dict) == 0 + assert isinstance(param_dict, dict) + assert isinstance(param_dict, ParDict) + + def test_user_can_create_parameter_dictionary_with_initial_data(self, sample_par_objects) -> None: + """ + User can create a parameter dictionary with initial configuration data. + + GIVEN: A user has existing parameter data to work with + WHEN: They create a new ParDict with initial data + THEN: The dictionary should contain all provided parameters + """ + # Arrange: Initial data is provided via fixture + + # Act: Create parameter dictionary with initial data + param_dict = ParDict(sample_par_objects) + + # Assert: Dictionary contains all initial parameters + assert len(param_dict) == 5 + assert param_dict["ACRO_YAW_P"].value == 4.5 + assert param_dict["PILOT_SPEED_UP"].comment == "Pilot controlled climb rate" + assert "BATT_CAPACITY" in param_dict + + def test_user_can_create_parameter_dictionary_with_none_initial_data(self) -> None: + """ + User can create a parameter dictionary when initial data is None. + + GIVEN: A user passes None as initial data + WHEN: They create a new ParDict + THEN: An empty dictionary should be created without errors + """ + # Arrange & Act: Create parameter dictionary with None + param_dict = ParDict(None) + + # Assert: Dictionary is empty and functional + assert len(param_dict) == 0 + assert isinstance(param_dict, ParDict) + + +class TestParameterFileLoading: + """Test parameter file loading workflows.""" + + def test_user_can_load_missionplanner_style_parameter_file(self, temp_param_file) -> None: + """ + User can load parameters from a Mission Planner style file. + + GIVEN: A user has a Mission Planner format parameter file + WHEN: They load the file using load_param_file_into_dict + THEN: All parameters should be loaded with correct values and comments + """ + # Arrange: Temporary file is provided by fixture + + # Act: Load parameters from file + param_dict = ParDict.load_param_file_into_dict(temp_param_file) + + # Assert: Parameters loaded correctly + assert len(param_dict) == 5 + assert param_dict["ACRO_YAW_P"].value == 4.5 + assert param_dict["ACRO_YAW_P"].comment == "Yaw P gain" + assert param_dict["GPS_TYPE"].value == 1.0 + assert param_dict["GPS_TYPE"].comment is None # No comment in file + + def test_user_can_load_mavproxy_style_parameter_file(self, temp_mavproxy_file) -> None: + """ + User can load parameters from a MAVProxy style file. + + GIVEN: A user has a MAVProxy format parameter file (space-separated) + WHEN: They load the file using load_param_file_into_dict + THEN: All parameters should be loaded correctly + """ + # Arrange: MAVProxy style file provided by fixture + + # Act: Load parameters from MAVProxy file + param_dict = ParDict.load_param_file_into_dict(temp_mavproxy_file) + + # Assert: Parameters loaded correctly from space-separated format + assert len(param_dict) == 3 + assert param_dict["ACRO_YAW_P"].value == 4.5 + assert param_dict["PILOT_SPEED_UP"].value == 250.0 + assert param_dict["BATT_CAPACITY"].value == 5000.0 + + def test_user_can_create_pardict_from_file_using_class_method(self, temp_param_file) -> None: + """ + User can create a ParDict directly from a file using the from_file class method. + + GIVEN: A user has a parameter file to load + WHEN: They use ParDict.from_file() class method + THEN: A new ParDict instance should be created with all file parameters + """ + # Arrange: Parameter file provided by fixture + + # Act: Create ParDict from file + param_dict = ParDict.from_file(temp_param_file) + + # Assert: ParDict created with all file parameters + assert isinstance(param_dict, ParDict) + assert len(param_dict) == 5 + assert param_dict["BATT_CAPACITY"].value == 5000.0 + + def test_user_receives_error_for_invalid_parameter_file(self) -> None: + """ + User receives clear error when loading an invalid parameter file. + + GIVEN: A user tries to load a file with invalid parameter format + WHEN: They use load_param_file_into_dict on the invalid file + THEN: A SystemExit should be raised with descriptive error message + """ + # Arrange: Create temporary file with invalid content + invalid_content = """INVALID_LINE_WITHOUT_SEPARATOR +VALID_PARAM,1.0""" + + with tempfile.NamedTemporaryFile(mode="w", suffix=".param", delete=False) as f: + f.write(invalid_content) + f.flush() + + # Act & Assert: User gets clear error for invalid format + with pytest.raises(SystemExit, match="Missing parameter-value separator"): + ParDict.load_param_file_into_dict(f.name) + + os.unlink(f.name) + + def test_user_receives_error_for_duplicate_parameters(self) -> None: + """ + User receives error when file contains duplicate parameter names. + + GIVEN: A user has a parameter file with duplicate parameter names + WHEN: They try to load the file + THEN: A SystemExit should be raised indicating the duplication + """ + # Arrange: Create file with duplicate parameters + duplicate_content = """ACRO_YAW_P,4.5 +ACRO_YAW_P,6.0 # Duplicate parameter""" + + with tempfile.NamedTemporaryFile(mode="w", suffix=".param", delete=False) as f: + f.write(duplicate_content) + f.flush() + + # Act & Assert: User gets error for duplicate parameters + with pytest.raises(SystemExit, match="Duplicated parameter"): + ParDict.load_param_file_into_dict(f.name) + + os.unlink(f.name) + + +class TestParameterFileExporting: + """Test parameter file exporting workflows.""" + + def test_user_can_export_parameters_to_missionplanner_format(self, parameter_dict) -> None: + """ + User can export parameters to Mission Planner format file. + + GIVEN: A user has a configured parameter dictionary + WHEN: They export to a file using Mission Planner format + THEN: Parameters should be saved in comma-separated format with comments + """ + # Arrange: Create temporary output file + with tempfile.NamedTemporaryFile(mode="w", suffix=".param", delete=False) as f: + output_file = f.name + + try: + # Act: Export parameters to Mission Planner format + parameter_dict.export_to_param(output_file, "missionplanner") + + # Assert: File contains correctly formatted parameters + with open(output_file, encoding="utf-8") as f: + content = f.read() + + assert "ACRO_YAW_P,4.5 # Yaw P gain" in content + assert "GPS_TYPE,1" in content # No comment + assert len(content.splitlines()) >= 5 # At least 5 parameters + finally: + os.unlink(output_file) + + def test_user_can_export_parameters_to_mavproxy_format(self, parameter_dict) -> None: + """ + User can export parameters to MAVProxy format file. + + GIVEN: A user has a configured parameter dictionary + WHEN: They export to a file using MAVProxy format + THEN: Parameters should be saved in space-separated format + """ + # Arrange: Create temporary output file + with tempfile.NamedTemporaryFile(mode="w", suffix=".param", delete=False) as f: + output_file = f.name + + try: + # Act: Export parameters to MAVProxy format + parameter_dict.export_to_param(output_file, "mavproxy") + + # Assert: File contains space-separated format + with open(output_file, encoding="utf-8") as f: + content = f.read() + + # MAVProxy format uses fixed-width columns + assert "ACRO_YAW_P 4.500000 # Yaw P gain" in content + assert "GPS_TYPE 1.000000" in content + finally: + os.unlink(output_file) + + def test_user_can_export_parameters_with_custom_header(self, parameter_dict) -> None: + """ + User can export parameters with custom header content. + + GIVEN: A user wants to add custom header information to exported file + WHEN: They export with content_header parameter + THEN: The header should appear at the top of the exported file + """ + # Arrange: Prepare custom header and output file + custom_header = ["# Custom vehicle configuration", "# Generated on 2024-01-01"] + + with tempfile.NamedTemporaryFile(mode="w", suffix=".param", delete=False) as f: + output_file = f.name + + try: + # Act: Export with custom header + parameter_dict.export_to_param(output_file, content_header=custom_header) + + # Assert: File starts with custom header + with open(output_file, encoding="utf-8") as f: + lines = f.readlines() + + assert lines[0].strip() == "# Custom vehicle configuration" + assert lines[1].strip() == "# Generated on 2024-01-01" + assert "ACRO_YAW_P" in lines[2] # Parameters start after header + finally: + os.unlink(output_file) + + +class TestParameterMergingWorkflows: + """Test parameter merging and appending workflows.""" + + def test_user_can_merge_parameters_from_another_dictionary(self, parameter_dict, alternate_parameter_dict) -> None: + """ + User can merge parameters from another dictionary to update their configuration. + + GIVEN: A user has an existing parameter configuration + WHEN: They append parameters from another ParDict + THEN: Parameters should be merged with newer values replacing existing ones + """ + # Arrange: Two parameter dictionaries with some overlapping parameters + original_count = len(parameter_dict) + + # Act: User merges parameters from alternate dictionary + parameter_dict.append(alternate_parameter_dict) + + # Assert: Parameters merged correctly + assert len(parameter_dict) == original_count + 1 # One new parameter added + assert parameter_dict["ACRO_YAW_P"].value == 6.0 # Updated value + assert parameter_dict["NEW_PARAM"].value == 100.0 # New parameter added + assert parameter_dict["COMPASS_ENABLE"].value == 1.0 # Unchanged parameter preserved + + def test_user_can_append_parameters_to_empty_dictionary(self, empty_parameter_dict, alternate_parameter_dict) -> None: + """ + User can append parameters to an initially empty dictionary. + + GIVEN: A user starts with an empty parameter dictionary + WHEN: They append parameters from another dictionary + THEN: All parameters should be added to the empty dictionary + """ + # Arrange: Empty dictionary and source dictionary + source_count = len(alternate_parameter_dict) + + # Act: User appends parameters to empty dictionary + empty_parameter_dict.append(alternate_parameter_dict) + + # Assert: All parameters copied to previously empty dictionary + assert len(empty_parameter_dict) == source_count + assert empty_parameter_dict["ACRO_YAW_P"].value == 6.0 + assert empty_parameter_dict["NEW_PARAM"].comment == "New parameter" + + def test_user_receives_error_when_appending_invalid_type(self, parameter_dict) -> None: + """ + User receives clear error when trying to append incompatible data types. + + GIVEN: A user has a valid parameter dictionary + WHEN: They try to append data that is not an ParDict + THEN: A TypeError should be raised with a helpful message + """ + # Arrange: Invalid data to append + invalid_data = {"PARAM": Par(1.0)} + + # Act & Assert: User gets helpful error message + with pytest.raises(TypeError, match="Can only append another ParDict instance"): + parameter_dict.append(invalid_data) + + +class TestParameterComparisonWorkflows: + """Test parameter comparison and filtering workflows.""" + + def test_user_can_remove_parameters_with_same_values_but_different_comments(self, parameter_dict) -> None: + """ + User can remove parameters that have the same values but different comments. + + GIVEN: A user has FC parameters (no comments) and file parameters (with comments) with same values + WHEN: They remove parameters with similar values using remove_if_value_is_similar + THEN: Parameters with matching values should be removed regardless of comment differences + """ + # Arrange: Create a dictionary with parameters that have same values but different comments + file_params_with_comments = ParDict( + { + "ACRO_YAW_P": Par(4.5, "Yaw rate controller P gain"), # Same value, different comment + "COMPASS_ENABLE": Par(1.0, "Enable compass sensor"), # Same value, different comment + "NEW_PARAM": Par(999.0, "This parameter doesn't exist in original"), # Different parameter + } + ) + + original_count = len(parameter_dict) + + # Act: User removes parameters with similar values + parameter_dict.remove_if_value_is_similar(file_params_with_comments) + + # Assert: Parameters with matching values were removed, regardless of comments + assert len(parameter_dict) == original_count - 2 # Two parameters removed + assert "ACRO_YAW_P" not in parameter_dict # Same value, removed despite different comment + assert "COMPASS_ENABLE" not in parameter_dict # Same value, removed despite different comment + assert "PILOT_SPEED_UP" in parameter_dict # Different value, kept + assert "BATT_CAPACITY" in parameter_dict # Not in other dict, kept + assert "GPS_TYPE" in parameter_dict # Not in other dict, kept + + def test_user_receives_error_when_comparing_with_invalid_type(self, parameter_dict) -> None: + """ + User receives error when trying to compare with non-ParDict objects. + + GIVEN: A user has a valid parameter dictionary + WHEN: They try to use remove_if_value_is_similar with non-ParDict data + THEN: A TypeError should be raised with helpful message + """ + # Arrange: Invalid comparison data + invalid_data = {"PARAM": 1.0} + + # Act & Assert: User gets clear error message + with pytest.raises(TypeError, match="Can only compare with another ParDict instance"): + parameter_dict.remove_if_value_is_similar(invalid_data) + + def test_user_can_find_missing_or_different_parameters(self, parameter_dict, alternate_parameter_dict) -> None: + """ + User can identify parameters that are missing or have different values in another dictionary. + + GIVEN: A user has two parameter configurations to compare + WHEN: They use get_missing_or_different to find differences + THEN: Only parameters that are missing or have different values should be returned + """ + # Arrange: Two dictionaries with some differences + + # Act: Find missing or different parameters + differences = parameter_dict.get_missing_or_different(alternate_parameter_dict) + + # Assert: Only different/missing parameters identified + assert "PILOT_SPEED_UP" in differences # Missing in alternate + assert "BATT_CAPACITY" in differences # Missing in alternate + assert "GPS_TYPE" in differences # Missing in alternate + assert "ACRO_YAW_P" in differences # Different value (4.5 vs 6.0) + assert "COMPASS_ENABLE" not in differences # Same value in both + + +class TestParameterCreationFromDifferentSources: + """Test creating ParDict from various data sources.""" + + def test_user_can_create_pardict_from_float_dictionary(self) -> None: + """ + User can create a ParDict from a simple float dictionary. + + GIVEN: A user has flight controller parameters as float values + WHEN: They convert them to ParDict using from_float_dict + THEN: A ParDict with Par objects should be created with default comments + """ + # Arrange: Simple float dictionary (like FC parameters) + float_params = { + "ACRO_YAW_P": 4.5, + "PILOT_SPEED_UP": 250.0, + "BATT_CAPACITY": 5000.0, + } + + # Act: Create ParDict from float dictionary + param_dict = ParDict.from_float_dict(float_params, "FC parameter") + + # Assert: ParDict created with default comments + assert len(param_dict) == 3 + assert param_dict["ACRO_YAW_P"].value == 4.5 + assert param_dict["ACRO_YAW_P"].comment == "FC parameter" + assert param_dict["PILOT_SPEED_UP"].value == 250.0 + + def test_user_can_create_pardict_from_fc_parameters(self) -> None: + """ + User can create a ParDict from flight controller parameters. + + GIVEN: A user receives parameters from a flight controller + WHEN: They convert them using from_fc_parameters + THEN: A ParDict should be created with empty comments + """ + # Arrange: FC parameters (typically just floats) + fc_params = { + "ACRO_YAW_P": 4.5, + "GPS_TYPE": 1.0, + } + + # Act: Create ParDict from FC parameters + param_dict = ParDict.from_fc_parameters(fc_params) + + # Assert: ParDict created with no comments (FC default) + assert len(param_dict) == 2 + assert param_dict["ACRO_YAW_P"].value == 4.5 + assert param_dict["ACRO_YAW_P"].comment == "" # Default empty comment + assert param_dict["GPS_TYPE"].value == 1.0 + + +class TestParameterFiltering: + """Test parameter filtering by various criteria.""" + + def test_user_can_filter_parameters_by_default_values(self, parameter_dict, default_parameters) -> None: + """ + User can filter out parameters that match default values. + + GIVEN: A user has current parameters and default parameter values + WHEN: They filter by defaults using _filter_by_defaults + THEN: Only parameters that differ from defaults should remain + """ + # Arrange: Parameters with some matching defaults + + # Act: Filter out parameters that match defaults + non_default = parameter_dict._filter_by_defaults(default_parameters) # pylint: disable=protected-access + + # Assert: Only non-default parameters remain + assert "ACRO_YAW_P" not in non_default # Same as default + assert "PILOT_SPEED_UP" in non_default # Different from default (250 vs 200) + assert "BATT_CAPACITY" in non_default # Not in defaults + assert "GPS_TYPE" in non_default # Not in defaults + + def test_user_can_filter_parameters_by_default_values_with_tolerance(self, parameter_dict, default_parameters) -> None: + """ + User can filter parameters by defaults using a tolerance function. + + GIVEN: A user wants to filter parameters with a tolerance for floating point comparison + WHEN: They provide a tolerance function to _filter_by_defaults + THEN: Parameters within tolerance should be filtered out + """ + + # Arrange: Define tolerance function + def tolerance_func(val1: float, val2: float) -> bool: + return abs(val1 - val2) < 100.0 # 100 unit tolerance + + # Act: Filter with tolerance + non_default = parameter_dict._filter_by_defaults(default_parameters, tolerance_func) # pylint: disable=protected-access + + # Assert: Parameters within tolerance are filtered + assert "PILOT_SPEED_UP" not in non_default # 250 vs 200 = 50 difference (within tolerance) + assert "BATT_CAPACITY" in non_default # Not in defaults, so kept + + def test_user_can_filter_readonly_parameters(self, parameter_dict, documentation_dict) -> None: + """ + User can identify read-only parameters using documentation. + + GIVEN: A user has parameters and documentation indicating read-only status + WHEN: They filter by read-only status + THEN: Only read-only parameters should be returned + """ + # Arrange: Documentation indicates PILOT_SPEED_UP is read-only + + # Act: Filter read-only parameters + readonly_params = parameter_dict._filter_by_readonly(documentation_dict) # pylint: disable=protected-access + + # Assert: Only read-only parameters identified + assert len(readonly_params) == 1 + assert "PILOT_SPEED_UP" in readonly_params # Marked as ReadOnly: True + assert "ACRO_YAW_P" not in readonly_params # Marked as ReadOnly: False + + def test_user_can_filter_calibration_parameters(self, parameter_dict, documentation_dict) -> None: + """ + User can identify calibration parameters using documentation. + + GIVEN: A user has parameters and documentation indicating calibration status + WHEN: They filter by calibration status + THEN: Only calibration parameters should be returned + """ + # Arrange: Documentation indicates BATT_CAPACITY and COMPASS_ENABLE are calibration + + # Act: Filter calibration parameters + calibration_params = parameter_dict._filter_by_calibration(documentation_dict) # pylint: disable=protected-access + + # Assert: Only calibration parameters identified + assert len(calibration_params) == 2 + assert "BATT_CAPACITY" in calibration_params # Marked as Calibration: True + assert "COMPASS_ENABLE" in calibration_params # Marked as Calibration: True + assert "ACRO_YAW_P" not in calibration_params # Marked as Calibration: False + + def test_user_can_categorize_parameters_by_documentation( + self, parameter_dict, default_parameters, documentation_dict + ) -> None: + """ + User can categorize parameters into read-only, calibration, and other categories. + + GIVEN: A user has parameters with documentation and default values + WHEN: They categorize using categorize_by_documentation + THEN: Parameters should be sorted into appropriate categories + """ + # Arrange: Parameters, defaults, and documentation provided by fixtures + + # Act: Categorize parameters + readonly, calibration, other = parameter_dict.categorize_by_documentation(documentation_dict, default_parameters) + + # Assert: Parameters categorized correctly + # Note: Only non-default parameters are categorized + assert "PILOT_SPEED_UP" in readonly # Read-only and non-default + assert "BATT_CAPACITY" in calibration # Calibration and non-default + assert "GPS_TYPE" in other # Neither read-only nor calibration, non-default + + +class TestParameterUtilities: + """Test utility methods for parameter handling.""" + + def test_user_can_sort_parameters_using_missionplanner_rules(self) -> None: + """ + User can sort parameter names using Mission Planner sorting rules. + + GIVEN: A user has parameter names that need to be sorted + WHEN: They use missionplanner_sort function + THEN: Parameters should be sorted by component parts + """ + # Arrange: Parameter names with different patterns + param_names = ["BATT_CAPACITY", "ACRO_YAW_P", "BATT_MONITOR", "ACRO_PITCH_P"] + + # Act: Sort using Mission Planner rules + sorted_names = sorted(param_names, key=ParDict.missionplanner_sort) + + # Assert: Parameters sorted by component groups + assert sorted_names[0].startswith("ACRO") + assert sorted_names[1].startswith("ACRO") + assert sorted_names[2].startswith("BATT") + assert sorted_names[3].startswith("BATT") + + def test_user_can_format_parameters_for_missionplanner(self, parameter_dict) -> None: + """ + User can format parameters for Mission Planner compatibility. + + GIVEN: A user has parameters to format for Mission Planner + WHEN: They use _format_params with missionplanner format + THEN: Parameters should be formatted with comma separation + """ + # Arrange: Parameter dictionary with mixed comments + + # Act: Format for Mission Planner + formatted = parameter_dict._format_params("missionplanner") # pylint: disable=protected-access + + # Assert: Correct Mission Planner format + assert any("ACRO_YAW_P,4.5 # Yaw P gain" in line for line in formatted) + assert any("GPS_TYPE,1" in line for line in formatted) # No comment case + assert len(formatted) == 5 # All parameters formatted + + def test_user_can_format_parameters_for_mavproxy(self, parameter_dict) -> None: + """ + User can format parameters for MAVProxy compatibility. + + GIVEN: A user has parameters to format for MAVProxy + WHEN: They use _format_params with mavproxy format + THEN: Parameters should be formatted with space separation and fixed width + """ + # Arrange: Parameter dictionary + + # Act: Format for MAVProxy + formatted = parameter_dict._format_params("mavproxy") # pylint: disable=protected-access + + # Assert: Correct MAVProxy format (space-separated, fixed width) + yaw_line = next((line for line in formatted if "ACRO_YAW_P" in line), "") + assert yaw_line == "ACRO_YAW_P 4.500000 # Yaw P gain" + + def test_user_receives_error_for_unsupported_format(self, parameter_dict) -> None: + """ + User receives error when using unsupported export format. + + GIVEN: A user tries to format parameters with unsupported format + WHEN: They call _format_params with invalid format + THEN: A SystemExit should be raised with error message + """ + # Arrange: Invalid format string + + # Act & Assert: User gets error for unsupported format + with pytest.raises(SystemExit, match="Unsupported file format"): + parameter_dict._format_params("invalid_format") # pylint: disable=protected-access + + def test_user_can_annotate_parameters_with_comments(self, parameter_dict) -> None: + """ + User can add comments to parameters using a lookup table. + + GIVEN: A user has parameters without comments and a comment lookup + WHEN: They use annotate_with_comments + THEN: Parameters should be updated with comments from lookup + """ + # Arrange: Comment lookup table + comment_lookup = { + "ACRO_YAW_P": "Updated yaw P gain comment", + "GPS_TYPE": "GPS receiver type selection", + "NEW_PARAM": "This param doesn't exist", + } + + # Act: Annotate with comments + annotated = parameter_dict.annotate_with_comments(comment_lookup) + + # Assert: Comments updated from lookup + assert annotated["ACRO_YAW_P"].comment == "Updated yaw P gain comment" + assert annotated["GPS_TYPE"].comment == "GPS receiver type selection" + assert annotated["PILOT_SPEED_UP"].comment == "Pilot controlled climb rate" # Original preserved + + @patch("ardupilot_methodic_configurator.data_model_par_dict.os_popen") + def test_user_can_print_parameter_list_with_pagination(self, mock_popen) -> None: + """ + User can print long parameter lists with automatic pagination. + + GIVEN: A user has a long list of formatted parameters + WHEN: They use print_out static method + THEN: Parameters should be printed with pagination control + """ + # Arrange: Mock terminal size and formatted parameters + mock_popen.return_value.read.return_value = "25 80" # 25 rows, 80 columns + formatted_params = [f"PARAM_{i},1.0" for i in range(50)] # Long list + + # Act: Print with pagination (capture in StringIO since we can't easily test print) + with patch("builtins.print") as mock_print: + ParDict.print_out(formatted_params, "Test Parameters") + + # Assert: Print called with pagination info + mock_print.assert_any_call("\nTest Parameters has 50 parameters:") + + +class TestParameterCategorization: + """Test parameter categorization workflows by documentation.""" + + def test_user_can_categorize_parameters_by_documentation_type( + self, parameter_dict, documentation_dict, default_parameters + ) -> None: + """ + User can categorize parameters into read-only, calibration, and other types. + + GIVEN: A user has parameters with documentation metadata + WHEN: They categorize parameters by documentation type + THEN: Parameters should be properly sorted into read-only, calibration, and other categories + """ + # Arrange: Parameter dictionary with documentation + + # Act: Categorize parameters by documentation + readonly, calibration, other = parameter_dict.categorize_by_documentation(documentation_dict, default_parameters) + + # Assert: Parameters correctly categorized + assert "PILOT_SPEED_UP" in readonly # Marked as ReadOnly=True + assert "BATT_CAPACITY" in calibration # Marked as Calibration=True + assert "COMPASS_ENABLE" in calibration # Marked as Calibration=True + assert "ACRO_YAW_P" not in readonly # Not read-only + assert "ACRO_YAW_P" not in calibration # Not calibration + assert "GPS_TYPE" in other # Non-default, non-readonly, non-calibration + + def test_user_can_categorize_parameters_with_tolerance_function( + self, parameter_dict, documentation_dict, default_parameters + ) -> None: + """ + User can categorize parameters using a custom tolerance function for value comparison. + + GIVEN: A user has parameters and wants to use tolerance-based comparison + WHEN: They provide a tolerance function for categorization + THEN: Parameters should be categorized considering the tolerance + """ + + # Arrange: Custom tolerance function (always returns True for this test) + def always_within_tolerance(_value1: float, _value2: float) -> bool: + return True + + # Act: Categorize with tolerance function + readonly, calibration, other = parameter_dict.categorize_by_documentation( + documentation_dict, default_parameters, always_within_tolerance + ) + + # Assert: Only parameters not in defaults remain, but tolerance affects those that are + # PILOT_SPEED_UP should be filtered out by tolerance despite different value + assert "PILOT_SPEED_UP" not in readonly # Tolerance made it seem default + # Parameters not in defaults (BATT_CAPACITY, GPS_TYPE, COMPASS_ENABLE) still remain + assert len(readonly) == 0 # No readonly parameters after tolerance filtering + assert "BATT_CAPACITY" in calibration # Still non-default, still calibration + assert "COMPASS_ENABLE" in calibration # Still non-default, still calibration + assert "GPS_TYPE" in other # Still non-default, not readonly, not calibration + + +class TestParameterCommentAnnotation: + """Test parameter comment annotation workflows.""" + + def test_user_can_annotate_parameters_with_new_comments(self, parameter_dict) -> None: + """ + User can add or update comments on parameters from a lookup table. + + GIVEN: A user has parameters and wants to add descriptive comments + WHEN: They use annotate_with_comments with a comment lookup table + THEN: Parameters should have updated comments from the lookup table + """ + # Arrange: Comment lookup table + comment_lookup = { + "ACRO_YAW_P": "Updated yaw rate controller P gain", + "BATT_CAPACITY": "Battery capacity for flight planning", + "NEW_PARAM": "This parameter doesn't exist in original", + } + + # Act: Annotate parameters with new comments + annotated_params = parameter_dict.annotate_with_comments(comment_lookup) + + # Assert: Comments updated from lookup table + assert annotated_params["ACRO_YAW_P"].comment == "Updated yaw rate controller P gain" + assert annotated_params["BATT_CAPACITY"].comment == "Battery capacity for flight planning" + assert annotated_params["PILOT_SPEED_UP"].comment == "Pilot controlled climb rate" # Original comment preserved + + def test_user_can_preserve_original_comments_when_no_lookup_found(self, parameter_dict) -> None: + """ + User preserves original comments when no lookup entry is found. + + GIVEN: A user has parameters with existing comments and an incomplete lookup table + WHEN: They annotate parameters but some parameters are not in the lookup + THEN: Original comments should be preserved for parameters not in lookup + """ + # Arrange: Partial comment lookup + partial_lookup = { + "ACRO_YAW_P": "New yaw comment", + # PILOT_SPEED_UP not in lookup - should preserve original + } + + # Act: Annotate with partial lookup + annotated_params = parameter_dict.annotate_with_comments(partial_lookup) + + # Assert: Mixed comment sources + assert annotated_params["ACRO_YAW_P"].comment == "New yaw comment" # From lookup + assert annotated_params["PILOT_SPEED_UP"].comment == "Pilot controlled climb rate" # Original preserved + + +class TestParameterSortingBehavior: + """Test parameter sorting functionality.""" + + def test_user_gets_mission_planner_compatible_sorting(self) -> None: + """ + User gets parameters sorted in Mission Planner compatible order. + + GIVEN: A user has parameters that need to be sorted for Mission Planner + WHEN: They use missionplanner_sort function + THEN: Parameters should be sorted by underscore-separated parts + """ + # Arrange: Parameter names to sort + param_names = ["BATT_CAPACITY", "ACRO_YAW_P", "PILOT_SPEED_UP", "GPS_TYPE"] + + # Act: Sort using Mission Planner rules + sorted_names = sorted(param_names, key=ParDict.missionplanner_sort) + + # Assert: Correct alphabetical order by parts + expected_order = ["ACRO_YAW_P", "BATT_CAPACITY", "GPS_TYPE", "PILOT_SPEED_UP"] + assert sorted_names == expected_order + + def test_user_gets_consistent_parameter_sorting_with_underscore_parts(self) -> None: + """ + User gets consistent sorting when parameters have multiple underscore parts. + + GIVEN: A user has parameters with multiple underscore separators + WHEN: They sort using missionplanner_sort + THEN: Each part should be compared separately for consistent ordering + """ + # Arrange: Complex parameter names + complex_names = ["MOTOR_PWM_TYPE", "MOTOR_EXPO", "MOTOR_THST_EXPO", "MOTOR_PWM_MAX"] + + # Act: Sort using Mission Planner rules + sorted_names = sorted(complex_names, key=ParDict.missionplanner_sort) + + # Assert: Correct part-wise sorting + expected_order = ["MOTOR_EXPO", "MOTOR_PWM_MAX", "MOTOR_PWM_TYPE", "MOTOR_THST_EXPO"] + assert sorted_names == expected_order + + +class TestParameterParsingEdgeCases: + """Test edge cases in parameter file parsing.""" + + def test_user_can_parse_parameters_with_tab_separators(self) -> None: + """ + User can parse parameter files that use tab separators. + + GIVEN: A user has a parameter file with tab-separated values + WHEN: They load the parameter file + THEN: Parameters should be correctly parsed despite tab separators + """ + # Arrange: Parameter file with tab separators + tab_content = "ACRO_YAW_P\t4.5\t# Tab separated parameter\nPILOT_SPEED_UP\t250.0" + + with tempfile.NamedTemporaryFile(mode="w", suffix=".param", delete=False) as f: + f.write(tab_content) + f.flush() + + try: + # Act: Load parameter file with tabs + params = ParDict.load_param_file_into_dict(f.name) + + # Assert: Parameters parsed correctly + assert len(params) == 2 + assert params["ACRO_YAW_P"].value == 4.5 + assert params["ACRO_YAW_P"].comment == "Tab separated parameter" + assert params["PILOT_SPEED_UP"].value == 250.0 + finally: + os.unlink(f.name) + + def test_user_receives_clear_error_for_missing_separators(self) -> None: + """ + User receives clear error when parameter files lack proper separators. + + GIVEN: A user has a malformed parameter file without proper separators + WHEN: They try to load the parameter file + THEN: A clear error message should be provided about missing separators + """ + # Arrange: Malformed parameter content (no separator) + malformed_content = "PARAM_WITHOUT_SEPARATOR_VALUE" + + with tempfile.NamedTemporaryFile(mode="w", suffix=".param", delete=False) as f: + f.write(malformed_content) + f.flush() + + try: + # Act & Assert: Clear error for missing separator + with pytest.raises(SystemExit, match="Missing parameter-value separator"): + ParDict.load_param_file_into_dict(f.name) + finally: + os.unlink(f.name) + + def test_user_receives_error_for_too_long_parameter_names(self) -> None: + """ + User receives error when parameter names exceed maximum length. + + GIVEN: A user has a parameter file with names that are too long + WHEN: They try to load the parameter file + THEN: A clear error should be provided about parameter name length + """ + # Arrange: Parameter name longer than 16 characters + long_name = "A" * 17 # 17 characters (max is 16) + long_param_content = f"{long_name},1.0" + + with tempfile.NamedTemporaryFile(mode="w", suffix=".param", delete=False) as f: + f.write(long_param_content) + f.flush() + + try: + # Act & Assert: Error for too long parameter name + with pytest.raises(SystemExit, match="Too long parameter name"): + ParDict.load_param_file_into_dict(f.name) + finally: + os.unlink(f.name) + + def test_user_receives_error_for_invalid_parameter_name_characters(self) -> None: + """ + User receives error when parameter names contain invalid characters. + + GIVEN: A user has a parameter file with invalid characters in names + WHEN: They try to load the parameter file + THEN: A clear error should be provided about invalid characters + """ + # Arrange: Parameter name with invalid characters (lowercase not allowed) + invalid_content = "invalid_name,1.0" + + with tempfile.NamedTemporaryFile(mode="w", suffix=".param", delete=False) as f: + f.write(invalid_content) + f.flush() + + try: + # Act & Assert: Error for invalid characters + with pytest.raises(SystemExit, match="Invalid characters in parameter name"): + ParDict.load_param_file_into_dict(f.name) + finally: + os.unlink(f.name) + + def test_user_receives_error_for_duplicate_parameter_names(self) -> None: + """ + User receives error when parameter files contain duplicate parameter names. + + GIVEN: A user has a parameter file with duplicate parameter names + WHEN: They try to load the parameter file + THEN: A clear error should be provided about parameter duplication + """ + # Arrange: Parameter file with duplicates + duplicate_content = "ACRO_YAW_P,4.5\nACRO_YAW_P,6.0" + + with tempfile.NamedTemporaryFile(mode="w", suffix=".param", delete=False) as f: + f.write(duplicate_content) + f.flush() + + try: + # Act & Assert: Error for duplicate parameters + with pytest.raises(SystemExit, match="Duplicated parameter"): + ParDict.load_param_file_into_dict(f.name) + finally: + os.unlink(f.name) + + def test_user_can_parse_parameters_with_leading_and_trailing_whitespace(self) -> None: + """ + User can parse parameter files with various whitespace around parameter names and values. + + GIVEN: A user has a parameter file with inconsistent whitespace formatting + WHEN: They load the parameter file + THEN: Parameters should be correctly parsed with whitespace stripped + """ + # Arrange: Parameter file with various whitespace scenarios + whitespace_content = ( + " PARAM1 , 1.5 \n\tPARAM2\t,\t2.5\t\n PARAM3 3.5 \n\t PARAM4\t \t4.5 \t\n\t\tPARAM5\t\t,\t\t5.5\t\t" + ) + + with tempfile.NamedTemporaryFile(mode="w", suffix=".param", delete=False) as f: + f.write(whitespace_content) + f.flush() + + try: + # Act: Load parameter file with whitespace + params = ParDict.load_param_file_into_dict(f.name) + + # Assert: All parameters parsed correctly with whitespace stripped + assert len(params) == 5 + assert params["PARAM1"].value == 1.5 + assert params["PARAM2"].value == 2.5 + assert params["PARAM3"].value == 3.5 + assert params["PARAM4"].value == 4.5 + assert params["PARAM5"].value == 5.5 + finally: + os.unlink(f.name) + + def test_user_can_parse_parameters_with_mixed_separator_and_whitespace_combinations(self) -> None: + """ + User can parse parameter files with mixed separators and whitespace combinations. + + GIVEN: A user has a parameter file mixing comma, space, and tab separators with whitespace + WHEN: They load the parameter file + THEN: All parameters should be correctly parsed regardless of separator type + """ + # Arrange: Mixed separator and whitespace combinations + mixed_content = " COMMA1 , 1.0 \n\tTAB2\t2.0\t\n SPACE3 3.0 \n\t COMMA_TAB\t,\t 4.0 \t\n TAB_SPACE \t 5.0 " + + with tempfile.NamedTemporaryFile(mode="w", suffix=".param", delete=False) as f: + f.write(mixed_content) + f.flush() + + try: + # Act: Load parameter file with mixed separators + params = ParDict.load_param_file_into_dict(f.name) + + # Assert: All parameters parsed correctly + assert len(params) == 5 + assert params["COMMA1"].value == 1.0 + assert params["TAB2"].value == 2.0 + assert params["SPACE3"].value == 3.0 + assert params["COMMA_TAB"].value == 4.0 + assert params["TAB_SPACE"].value == 5.0 + finally: + os.unlink(f.name) + + def test_user_can_parse_parameters_with_extreme_whitespace_scenarios(self) -> None: + """ + User can parse parameter files with extreme whitespace scenarios. + + GIVEN: A user has a parameter file with extreme amounts of whitespace + WHEN: They load the parameter file + THEN: Parameters should be parsed correctly with all whitespace properly handled + """ + # Arrange: Extreme whitespace scenarios + extreme_content = ( + "\t\t\tEXTREME1\t\t\t,\t\t\t1.0\t\t\t\n" + " EXTREME2 2.0 \n" + "\t \t \tEXTREME3\t \t ,\t \t 3.0\t \t \n" + " EXTREME4 , 4.0 " + ) + + with tempfile.NamedTemporaryFile(mode="w", suffix=".param", delete=False) as f: + f.write(extreme_content) + f.flush() + + try: + # Act: Load parameter file with extreme whitespace + params = ParDict.load_param_file_into_dict(f.name) + + # Assert: All parameters parsed correctly despite extreme whitespace + assert len(params) == 4 + assert params["EXTREME1"].value == 1.0 + assert params["EXTREME2"].value == 2.0 + assert params["EXTREME3"].value == 3.0 + assert params["EXTREME4"].value == 4.0 + finally: + os.unlink(f.name) + + +class TestParameterDictionaryEdgeCases: + """Test edge cases and error conditions.""" + + def test_user_can_work_with_parameters_having_none_comments(self) -> None: + """ + User can work with parameters that have None comments without issues. + + GIVEN: A user has parameters with None comments + WHEN: They perform operations on these parameters + THEN: All operations should work correctly + """ + # Arrange: Parameters with None comments + params_with_none = { + "PARAM_1": Par(1.0, None), + "PARAM_2": Par(2.0, "Has comment"), + } + param_dict = ParDict(params_with_none) + + # Act & Assert: Operations work with None comments + assert len(param_dict) == 2 + assert param_dict["PARAM_1"].comment is None + assert param_dict["PARAM_2"].comment == "Has comment" + + def test_user_can_handle_empty_parameter_lists_gracefully(self) -> None: + """ + User can handle empty parameter lists without errors. + + GIVEN: A user has empty parameter dictionaries + WHEN: They perform operations on empty dictionaries + THEN: Operations should complete without errors + """ + # Arrange: Empty dictionaries + empty1 = ParDict() + empty2 = ParDict() + + # Act & Assert: Operations work with empty dictionaries + empty1.append(empty2) # Append empty to empty + assert len(empty1) == 0 + + empty1.remove_if_value_is_similar(empty2) # Remove from empty + assert len(empty1) == 0 + + differences = empty1.get_missing_or_different(empty2) + assert len(differences) == 0 + + def test_parameter_validation_rejects_invalid_names(self) -> None: + """ + Parameter validation rejects invalid parameter names. + + GIVEN: A user tries to load parameters with invalid names + WHEN: The validation process checks parameter names + THEN: Invalid names should be rejected with clear errors + """ + # Arrange: Invalid parameter content + invalid_names = [ + "lowercase_param,1.0", # Lowercase not allowed + "123_NUMERIC_START,1.0", # Can't start with number + "PARAM-WITH-DASH,1.0", # Dashes not allowed + "A" * 20 + ",1.0", # Too long + ] + + for invalid_content in invalid_names: + with tempfile.NamedTemporaryFile(mode="w", suffix=".param", delete=False) as f: + f.write(invalid_content) + f.flush() + + # Act & Assert: Invalid names rejected + with pytest.raises(SystemExit): + ParDict.load_param_file_into_dict(f.name) + + os.unlink(f.name) + + def test_parameter_validation_rejects_invalid_values(self) -> None: + """ + Parameter validation rejects invalid parameter values. + + GIVEN: A user tries to load parameters with invalid values + WHEN: The validation process checks parameter values + THEN: Invalid values should be rejected with clear errors + """ + # Arrange: Invalid parameter values + invalid_content = "VALID_PARAM,not_a_number" + + with tempfile.NamedTemporaryFile(mode="w", suffix=".param", delete=False) as f: + f.write(invalid_content) + f.flush() + + # Act & Assert: Invalid values rejected + with pytest.raises(SystemExit, match="Invalid parameter value"): + ParDict.load_param_file_into_dict(f.name) + + os.unlink(f.name) diff --git a/tests/test_frontend_tkinter_component_template_manager.py b/tests/test_frontend_tkinter_component_template_manager.py index bb3bcd200..481363ff9 100755 --- a/tests/test_frontend_tkinter_component_template_manager.py +++ b/tests/test_frontend_tkinter_component_template_manager.py @@ -240,7 +240,7 @@ def test_apply_template_missing_keys(self, template_manager, entry_widgets, mock WHEN: User applies the template to the component THEN: Only matching fields should be updated and other fields remain unchanged """ - _, update_callback, _ = mock_callbacks # pylint: disable=unused-variable + _, _update_callback, _ = mock_callbacks template = {"name": "Incomplete", "data": {"SomeOtherField": "value"}} with patch("tkinter.messagebox.showinfo"): diff --git a/tests/test_frontend_tkinter_flightcontroller_info.py b/tests/test_frontend_tkinter_flightcontroller_info.py index 514d3cb99..74255dffb 100755 --- a/tests/test_frontend_tkinter_flightcontroller_info.py +++ b/tests/test_frontend_tkinter_flightcontroller_info.py @@ -14,9 +14,9 @@ import pytest -from ardupilot_methodic_configurator.annotate_params import Par from ardupilot_methodic_configurator.backend_flightcontroller import FlightController from ardupilot_methodic_configurator.backend_flightcontroller_info import BackendFlightcontrollerInfo +from ardupilot_methodic_configurator.data_model_par_dict import Par from ardupilot_methodic_configurator.frontend_tkinter_flightcontroller_info import ( FlightControllerInfoPresenter, FlightControllerInfoWindow, diff --git a/tests/test_frontend_tkinter_parameter_editor.py b/tests/test_frontend_tkinter_parameter_editor.py index a46ca7ee4..f8af36981 100755 --- a/tests/test_frontend_tkinter_parameter_editor.py +++ b/tests/test_frontend_tkinter_parameter_editor.py @@ -16,7 +16,7 @@ import pytest from ardupilot_methodic_configurator import _ -from ardupilot_methodic_configurator.annotate_params import Par +from ardupilot_methodic_configurator.data_model_par_dict import Par from ardupilot_methodic_configurator.frontend_tkinter_parameter_editor import ParameterEditorWindow # pylint: disable=redefined-outer-name, too-many-arguments, too-many-positional-arguments, unused-argument diff --git a/tests/test_frontend_tkinter_parameter_editor_table.py b/tests/test_frontend_tkinter_parameter_editor_table.py index 0b5ed932b..7103e6acf 100755 --- a/tests/test_frontend_tkinter_parameter_editor_table.py +++ b/tests/test_frontend_tkinter_parameter_editor_table.py @@ -17,9 +17,9 @@ import pytest -from ardupilot_methodic_configurator.annotate_params import Par from ardupilot_methodic_configurator.backend_filesystem import LocalFilesystem from ardupilot_methodic_configurator.data_model_ardupilot_parameter import ArduPilotParameter +from ardupilot_methodic_configurator.data_model_par_dict import Par from ardupilot_methodic_configurator.frontend_tkinter_pair_tuple_combobox import ( PairTupleCombobox, setup_combobox_mousewheel_handling, diff --git a/tests/test_integration_parameter_editor_table.py b/tests/test_integration_parameter_editor_table.py index 78054d3fc..3ca1e030b 100755 --- a/tests/test_integration_parameter_editor_table.py +++ b/tests/test_integration_parameter_editor_table.py @@ -19,9 +19,9 @@ import pytest -from ardupilot_methodic_configurator.annotate_params import Par from ardupilot_methodic_configurator.backend_filesystem import LocalFilesystem from ardupilot_methodic_configurator.data_model_ardupilot_parameter import ArduPilotParameter +from ardupilot_methodic_configurator.data_model_par_dict import Par from ardupilot_methodic_configurator.frontend_tkinter_parameter_editor_table import ParameterEditorTable # pylint: disable=redefined-outer-name, protected-access diff --git a/tests/test_param_pid_adjustment_update.py b/tests/test_param_pid_adjustment_update.py index 00826f2a1..adb754439 100755 --- a/tests/test_param_pid_adjustment_update.py +++ b/tests/test_param_pid_adjustment_update.py @@ -22,7 +22,11 @@ import pytest -from ardupilot_methodic_configurator.param_pid_adjustment_update import Par, ranged_type, update_pid_adjustment_params +from ardupilot_methodic_configurator.param_pid_adjustment_update import ( + load_param_file_with_content, + ranged_type, + update_pid_adjustment_params, +) class TestRangedType(unittest.TestCase): @@ -30,17 +34,17 @@ class TestRangedType(unittest.TestCase): def test_valid_input(self) -> None: assert ranged_type(int, 1, 10)(5) == 5 - assert ranged_type(float, 0.1, 0.8)(0.5) == 0.5 + assert ranged_type(float, 0.1, 1.2)(0.5) == 0.5 def test_invalid_input(self) -> None: with pytest.raises(argparse.ArgumentTypeError) as cm: ranged_type(int, 1, 10)(15) assert cm.value.args[0] == "must be within [1, 10]" with pytest.raises(argparse.ArgumentTypeError) as cm: - ranged_type(float, 0.1, 0.8)(0.9) - assert cm.value.args[0] == "must be within [0.1, 0.8]" + ranged_type(float, 0.1, 1.2)(1.5) + assert cm.value.args[0] == "must be within [0.1, 1.2]" with pytest.raises(argparse.ArgumentTypeError) as cm: - ranged_type(float, 0.1, 0.8)("sf") + ranged_type(float, 0.1, 1.2)("sf") assert cm.value.args[0] == "must be a valid " @@ -55,7 +59,7 @@ def test_valid_input(self) -> None: f.write("PARAM3 3.0 # Comment\n") # Call the function and check the result - params, _ = Par.load_param_file_into_dict("temp.param") + params, _ = load_param_file_with_content("temp.param") assert len(params) == 2 assert params["PARAM1"].value == 1.0 assert params["PARAM3"].value == 3.0 @@ -67,10 +71,10 @@ def test_invalid_input(self) -> None: f.write("PARAM2\n") # Missing value f.write("PARAM3 3.0 # Invalid comment\n") - # Call the function and check that it raises an exception + # Call the function and check that it raises an exception with pytest.raises(SystemExit) as cm: - Par.load_param_file_into_dict("temp.param") - assert cm.value.args[0] == "Missing parameter-value separator: PARAM2 in temp.param line 2" + load_param_file_with_content("temp.param") + assert "Missing parameter-value separator:" in str(cm.value) def test_empty_file(self) -> None: # Create an empty temporary file @@ -78,7 +82,7 @@ def test_empty_file(self) -> None: pass # Call the function and check the result - params, _ = Par.load_param_file_into_dict("temp.param") + params, _ = load_param_file_with_content("temp.param") assert len(params) == 0 def test_only_comments(self) -> None: @@ -88,7 +92,7 @@ def test_only_comments(self) -> None: f.write("# Comment 2\n") # Call the function and check the result - params, _ = Par.load_param_file_into_dict("temp.param") + params, _ = load_param_file_with_content("temp.param") assert len(params) == 0 def test_missing_value(self) -> None: @@ -98,7 +102,7 @@ def test_missing_value(self) -> None: # Call the function and check that it raises an exception with pytest.raises(SystemExit) as cm: - Par.load_param_file_into_dict("temp.param") + load_param_file_with_content("temp.param") assert cm.value.args[0] == "Missing parameter-value separator: PARAM1 in temp.param line 1" def test_space_separator(self) -> None: @@ -107,7 +111,7 @@ def test_space_separator(self) -> None: f.write("PARAM1 1.0\n") # Call the function and check the result - params, _ = Par.load_param_file_into_dict("temp.param") + params, _ = load_param_file_with_content("temp.param") assert params["PARAM1"].value == 1.0 def test_comma_separator(self) -> None: @@ -116,7 +120,7 @@ def test_comma_separator(self) -> None: f.write("PARAM1,1.0\n") # Call the function and check the result - params, _ = Par.load_param_file_into_dict("temp.param") + params, _ = load_param_file_with_content("temp.param") assert params["PARAM1"].value == 1.0 def test_tab_separator(self) -> None: @@ -125,7 +129,7 @@ def test_tab_separator(self) -> None: f.write("PARAM1\t1.0\n") # Call the function and check the result - params, _ = Par.load_param_file_into_dict("temp.param") + params, _ = load_param_file_with_content("temp.param") assert params["PARAM1"].value == 1.0 def test_invalid_characters(self) -> None: @@ -135,7 +139,7 @@ def test_invalid_characters(self) -> None: # Call the function and check that it raises an exception with pytest.raises(SystemExit) as cm: - Par.load_param_file_into_dict("temp.param") + load_param_file_with_content("temp.param") assert cm.value.args[0] == "Invalid characters in parameter name PARAM-1 in temp.param line 1" def test_long_parameter_name(self) -> None: @@ -145,7 +149,7 @@ def test_long_parameter_name(self) -> None: # Call the function and check that it raises an exception with pytest.raises(SystemExit) as cm: - Par.load_param_file_into_dict("temp.param") + load_param_file_with_content("temp.param") assert cm.value.args[0] == "Too long parameter name: PARAMETER_THAT_IS_TOO_LONG in temp.param line 1" def test_invalid_value(self) -> None: @@ -155,7 +159,7 @@ def test_invalid_value(self) -> None: # Call the function and check that it raises an exception with pytest.raises(SystemExit) as cm: - Par.load_param_file_into_dict("temp.param") + load_param_file_with_content("temp.param") assert cm.value.args[0] == "Invalid parameter value VALUE in temp.param line 1" def test_duplicated_parameter(self) -> None: @@ -166,7 +170,7 @@ def test_duplicated_parameter(self) -> None: # Call the function and check that it raises an exception with pytest.raises(SystemExit) as cm: - Par.load_param_file_into_dict("temp.param") + load_param_file_with_content("temp.param") assert cm.value.args[0] == "Duplicated parameter PARAM1 in temp.param line 2" def tearDown(self) -> None: @@ -186,10 +190,10 @@ def test_valid_input(self) -> None: f.write("PARAM3 3.0 # Comment\n") # Load the parameters into a dictionary - params, _ = Par.load_param_file_into_dict("temp.param") + params, _ = load_param_file_with_content("temp.param") # Export the parameters to a file - Par.export_to_param(params, "output.param") + params.export_to_param("output.param") # Check the contents of the output file with open("output.param", encoding="utf-8") as f: @@ -205,10 +209,10 @@ def test_with_header(self) -> None: f.write("PARAM3 3.0\n") # Load the parameters into a dictionary - params, _ = Par.load_param_file_into_dict("temp.param") + params, _ = load_param_file_with_content("temp.param") # Export the parameters to a file, including the header - Par.export_to_param(params, "output.param", ["# HEADER"]) + params.export_to_param("output.param", content_header=["# HEADER"]) # Check the contents of the output file with open("output.param", encoding="utf-8") as f: