diff --git a/.flake8 b/.flake8 index eb61d04..dcd7cbd 100644 --- a/.flake8 +++ b/.flake8 @@ -13,4 +13,4 @@ ignore = E261 -max-line-length = 127 +max-line-length = 128 diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 9b7f9af..a112437 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -1,12 +1,18 @@ repos: - repo: https://github.com/astral-sh/ruff-pre-commit - rev: v0.7.1 + rev: v0.7.2 hooks: - id: ruff - args: [ --fix ] + args: [ --select=F,E,W,I,PL,RUF,PERF --line-length=127 --ignore=E501,PLR0911,PLR0912,PLR0913,PLR0915,PLR2004,PLW0603,PERF401,PLW2901,PERF203,RUF005 --fix ] language: system types: [python] stages: [pre-commit] + # Run the formatter. + - id: ruff-format + args: [ --line-length=127 ] + types_or: [ python ] + stages: [pre-commit] + - repo: local hooks: - id: pylint diff --git a/MethodicConfigurator/__init__.py b/MethodicConfigurator/__init__.py index 786d1a7..170c5dd 100644 --- a/MethodicConfigurator/__init__.py +++ b/MethodicConfigurator/__init__.py @@ -1 +1,15 @@ -'''ArduPilot Methodic Configurator GUI application''' # pylint: skip-file +#!/usr/bin/env python3 + +""" +This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator + +SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas + +SPDX-License-Identifier: GPL-3.0-or-later +""" +# pylint: skip-file + +from MethodicConfigurator.internationalization import load_translation + + +_ = load_translation() diff --git a/MethodicConfigurator/annotate_params.py b/MethodicConfigurator/annotate_params.py index 8b3249f..df02ad2 100755 --- a/MethodicConfigurator/annotate_params.py +++ b/MethodicConfigurator/annotate_params.py @@ -22,21 +22,18 @@ SPDX-License-Identifier: GPL-3.0-or-later """ -from os import path as os_path -from os import popen as os_popen - +import argparse import glob +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 sys import exit as sys_exit from typing import Any, Dict, List, Optional, Tuple +from xml.etree import ElementTree as ET # no parsing, just data-structure manipulation -import argparse -import logging - -from xml.etree import ElementTree as ET # no parsing, just data-structure manipulation -from defusedxml import ElementTree as DET # just parsing, no data-structure manipulation - +from defusedxml import ElementTree as DET # just parsing, no data-structure manipulation # URL of the XML file BASE_URL = "https://autotest.ardupilot.org/Parameters/" @@ -45,53 +42,72 @@ 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_REGEX = r"^[A-Z][A-Z_0-9]*" PARAM_NAME_MAX_LEN = 16 -VERSION = '1.0' +VERSION = "1.0" def arg_parser(): - parser = argparse.ArgumentParser(description='Fetches on-line ArduPilot parameter documentation and adds it to the ' - 'specified file or to all *.param and *.parm files in the specified directory.') - parser.add_argument('target', - help='The target file or directory.', - ) - parser.add_argument('-d', '--delete-documentation-annotations', - action='store_true', - help='Delete parameter documentation annotations (comments above parameters). Defaults to %(default)s', - ) - parser.add_argument('-f', '--firmware-version', - default='latest', - help='Flight controller firmware version. Defaults to %(default)s.', - ) - parser.add_argument('-s', '--sort', - choices=['none', 'missionplanner', 'mavproxy'], - default='none', - help='Sort the parameters in the file. Defaults to %(default)s.', - ) - parser.add_argument('-t', '--vehicle-type', - choices=['AP_Periph', 'AntennaTracker', 'ArduCopter', 'ArduPlane', - 'ArduSub', 'Blimp', 'Heli', 'Rover', 'SITL'], - default='ArduCopter', - help='The type of the vehicle. Defaults to %(default)s.', - ) - parser.add_argument('-m', '--max-line-length', - type=int, default=100, - help='Maximum documentation line length. Defaults to %(default)s.', - ) - parser.add_argument('--verbose', action='store_true', - help='Increase output verbosity, print ReadOnly parameter list. Defaults to %(default)s.', - ) - parser.add_argument('-v', '--version', action='version', version=f'%(prog)s {VERSION}', - help='Display version information and exit.', - ) + parser = argparse.ArgumentParser( + description="Fetches on-line ArduPilot parameter documentation and adds it to the " + "specified file or to all *.param and *.parm files in the specified directory." + ) + parser.add_argument( + "target", + help="The target file or directory.", + ) + parser.add_argument( + "-d", + "--delete-documentation-annotations", + action="store_true", + help="Delete parameter documentation annotations (comments above parameters). Defaults to %(default)s", + ) + parser.add_argument( + "-f", + "--firmware-version", + default="latest", + help="Flight controller firmware version. Defaults to %(default)s.", + ) + parser.add_argument( + "-s", + "--sort", + choices=["none", "missionplanner", "mavproxy"], + default="none", + help="Sort the parameters in the file. Defaults to %(default)s.", + ) + parser.add_argument( + "-t", + "--vehicle-type", + choices=["AP_Periph", "AntennaTracker", "ArduCopter", "ArduPlane", "ArduSub", "Blimp", "Heli", "Rover", "SITL"], + default="ArduCopter", + help="The type of the vehicle. Defaults to %(default)s.", + ) + parser.add_argument( + "-m", + "--max-line-length", + type=int, + default=100, + help="Maximum documentation line length. Defaults to %(default)s.", + ) + parser.add_argument( + "--verbose", + action="store_true", + help="Increase output verbosity, print ReadOnly parameter list. Defaults to %(default)s.", + ) + parser.add_argument( + "-v", + "--version", + action="version", + version=f"%(prog)s {VERSION}", + help="Display version information and exit.", + ) args = parser.parse_args() if args.verbose: - logging.basicConfig(level=logging.INFO, format='%(levelname)s: %(message)s') + logging.basicConfig(level=logging.INFO, format="%(levelname)s: %(message)s") else: - logging.basicConfig(level=logging.WARNING, format='%(levelname)s: %(message)s') + logging.basicConfig(level=logging.WARNING, format="%(levelname)s: %(message)s") # Custom validation for --max-line-length def check_max_line_length(value): @@ -113,6 +129,7 @@ class Par: 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): self.value = value self.comment = comment @@ -123,7 +140,7 @@ def __eq__(self, other: object) -> bool: return False @staticmethod - def load_param_file_into_dict(param_file: str) -> Dict[str, 'Par']: + def load_param_file_into_dict(param_file: str) -> Dict[str, "Par"]: """ Loads an ArduPilot parameter file into a dictionary with name, value pairs. @@ -136,9 +153,9 @@ def load_param_file_into_dict(param_file: str) -> Dict[str, 'Par']: parameter_dict = {} try: with open(param_file, encoding="utf-8") as f_handle: - for i, line in enumerate(f_handle, start=1): - original_line = line - line = line.strip() + 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 @@ -198,7 +215,7 @@ def missionplanner_sort(item: str) -> Tuple[str, ...]: return tuple(parts) @staticmethod - def format_params(param_dict: Dict[str, 'Par'], file_format: str = "missionplanner") -> List[str]: # pylint: disable=too-many-branches + 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. @@ -228,8 +245,9 @@ def format_params(param_dict: Dict[str, 'Par'], file_format: str = "missionplann 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('.')}" - f" # {parameter.comment}") + formatted_params.append( + f"{key},{format(parameter.value, '.6f').rstrip('0').rstrip('.')}" f" # {parameter.comment}" + ) else: formatted_params.append(f"{key},{format(parameter.value, '.6f').rstrip('0').rstrip('.')}") else: @@ -261,7 +279,7 @@ def export_to_param(formatted_params: List[str], filename_out: str) -> None: return try: # Ensure newline character is LF, even on windows - with open(filename_out, "w", encoding="utf-8", newline='\n') as output_file: + with open(filename_out, "w", encoding="utf-8", newline="\n") as output_file: for line in formatted_params: output_file.write(line + "\n") except IOError as e: @@ -287,10 +305,10 @@ def print_out(formatted_params: List[str], name: str) -> None: rows = 100 # Get the size of the terminal if __name__ == "__main__": - rows, _columns = os_popen('stty size', 'r').read().split() + rows, _columns = os_popen("stty size", "r").read().split() # Convert rows to integer - rows = int(rows) - 2 # -2 for the next print and the input line + rows = int(rows) - 2 # -2 for the next print and the input line # Convert rows print(f"\n{name} has {len(formatted_params)} parameters:") @@ -299,8 +317,8 @@ def print_out(formatted_params: List[str], name: str) -> None: i += 1 if i % rows == 0 and __name__ == "__main__": input(f"\n{name} list is long hit enter to continue") - rows, _columns = os_popen('stty size', 'r').read().split() - rows = int(rows) - 2 # -2 for the next print and the input line + rows, _columns = os_popen("stty size", "r").read().split() + rows = int(rows) - 2 # -2 for the next print and the input line print(line) @@ -330,8 +348,8 @@ def get_xml_data(base_url: str, directory: str, filename: str, vehicle_type: str else: # No locally cached file exists, get it from the internet try: - from requests import get as requests_get # pylint: disable=import-outside-toplevel from requests import exceptions as requests_exceptions # pylint: disable=import-outside-toplevel + from requests import get as requests_get # pylint: disable=import-outside-toplevel except ImportError as exc: logging.critical("The requests package was not found") logging.critical("Please install it by running 'pip install requests' in your terminal.") @@ -347,7 +365,7 @@ def get_xml_data(base_url: str, directory: str, filename: str, vehicle_type: str logging.warning("Unable to fetch XML data: %s", e) # Send a GET request to the URL to the fallback (DEV) URL try: - url = BASE_URL + vehicle_type + '/' + PARAM_DEFINITION_XML_FILE + url = BASE_URL + vehicle_type + "/" + PARAM_DEFINITION_XML_FILE logging.warning("Falling back to the DEV XML file: %s", url) response = requests_get(url, timeout=5) if response.status_code != 200: @@ -373,7 +391,7 @@ def get_xml_data(base_url: str, directory: str, filename: str, vehicle_type: str def load_default_param_file(directory: str) -> Dict[str, Any]: # 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 = Par.load_param_file_into_dict(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") @@ -393,7 +411,7 @@ def remove_prefix(text: str, prefix: str) -> str: str: The string without the prefix. """ if text.startswith(prefix): - return text[len(prefix):] + return text[len(prefix) :] return text @@ -408,9 +426,7 @@ def split_into_lines(string_to_split: str, maximum_line_length: int) -> List[str Returns: List[str]: The list of lines. """ - doc_lines = re.findall( - r".{1," + str(maximum_line_length) + r"}(?:\s|$)", string_to_split - ) + doc_lines = re.findall(r".{1," + str(maximum_line_length) + r"}(?:\s|$)", string_to_split) # Remove trailing whitespace from each line return [line.rstrip() for line in doc_lines] @@ -448,7 +464,7 @@ def create_doc_dict(root: ET.Element, vehicle_type: str, max_line_length: int = fields[key] = f"{value} ({fields['UnitText']})" delete_unit_text = True if delete_unit_text: - del fields['UnitText'] + del fields["UnitText"] # the keys are the "code" attribute of the "values/value" sub-elements # the values are the text content of the "values/value" sub-elements values = {value.get("code"): value.text for value in param.findall("values/value")} @@ -503,11 +519,11 @@ def format_columns(values: Dict[str, Any], max_width: int = 105, max_columns: in for j in range(num_rows): row = [] for i in range(num_cols): - if i*num_rows + j < len(strings): - if i < num_cols - 1 and ((i+1)*num_rows + j < len(strings)): - row.append(strings[i*num_rows + j].ljust(col_width)) + if i * num_rows + j < len(strings): + if i < num_cols - 1 and ((i + 1) * num_rows + j < len(strings)): + row.append(strings[i * num_rows + j].ljust(col_width)) else: - row.append(strings[i*num_rows + j]) + row.append(strings[i * num_rows + j]) formatted_strings.append(" ".join(row)) return formatted_strings @@ -550,10 +566,9 @@ def extract_parameter_name_and_validate(line: str, filename: str, line_nr: int) logging.critical("Invalid line %d in file %s: %s", line_nr, filename, line) raise SystemExit("Invalid line in input file") 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'}: - logging.critical("Invalid parameter name %s on line %d in file %s", param_name, line_nr, - filename) + param_sep = line[param_len] # the character following the parameter name must be a separator + if param_sep not in {",", " ", "\t"}: + logging.critical("Invalid parameter name %s on line %d in file %s", param_name, line_nr, filename) raise SystemExit("Invalid parameter name") if param_len > PARAM_NAME_MAX_LEN: logging.critical("Too long parameter name on line %d in file %s", line_nr, filename) @@ -561,9 +576,13 @@ def extract_parameter_name_and_validate(line: str, filename: str, line_nr: int) return param_name -def update_parameter_documentation(doc: Dict[str, Any], target: str = '.', - sort_type: str = 'none', param_default_dict: Optional[Dict] = None, - delete_documentation_annotations = False) -> None: +def update_parameter_documentation( + doc: Dict[str, Any], + target: str = ".", + sort_type: str = "none", + param_default_dict: Optional[Dict] = None, + delete_documentation_annotations=False, +) -> None: """ Updates the parameter documentation in the target file or in all *.param,*.parm files of the target directory. @@ -588,8 +607,7 @@ def update_parameter_documentation(doc: Dict[str, Any], target: str = '.', param_files = [target] elif os_path.isdir(target): # If it's a directory, process all .param and .parm files in that directory - param_files = glob.glob(os_path.join(target, "*.param")) \ - + glob.glob(os_path.join(target, "*.parm")) + param_files = glob.glob(os_path.join(target, "*.param")) + glob.glob(os_path.join(target, "*.parm")) else: raise ValueError(f"Target '{target}' is neither a file nor a directory.") @@ -598,7 +616,6 @@ def update_parameter_documentation(doc: Dict[str, Any], target: str = '.', # Iterate over all the target ArduPilot parameter files for param_file in param_files: - if os_path.basename(param_file).endswith("24_inflight_magnetometer_fit_setup.param") and "MAGH_ALT_DELTA" not in doc: continue @@ -606,11 +623,19 @@ def update_parameter_documentation(doc: Dict[str, Any], target: str = '.', with open(param_file, "r", encoding="utf-8") as file: lines = file.readlines() - update_parameter_documentation_file(doc, sort_type, param_default_dict, param_file, lines, - delete_documentation_annotations) + update_parameter_documentation_file( + doc, sort_type, param_default_dict, param_file, lines, delete_documentation_annotations + ) -def update_parameter_documentation_file(doc, sort_type, param_default_dict, param_file, lines, # pylint: disable=too-many-locals, too-many-arguments - delete_documentation_annotations: bool): + +def update_parameter_documentation_file( # pylint: disable=too-many-locals, too-many-arguments + doc, + sort_type, + param_default_dict, + param_file, + lines, + delete_documentation_annotations: bool, +): new_lines = [] if os_path.basename(param_file).endswith("16_pid_adjustment.param"): new_lines.extend(lines[0:5]) # copy the first 6 lines verbatim @@ -623,8 +648,8 @@ def update_parameter_documentation_file(doc, sort_type, param_default_dict, para lines.sort(key=missionplanner_sort) if sort_type == "mavproxy": lines.sort(key=extract_parameter_name) - for n, line in enumerate(lines, start=1): - line = line.strip() + for n, f_line in enumerate(lines, start=1): + line = f_line.strip() if not line.startswith("#") and line: param_name = extract_parameter_name_and_validate(line, param_file, n) @@ -633,15 +658,15 @@ def update_parameter_documentation_file(doc, sort_type, param_default_dict, para # prefix the line with a comment derived from the dictionary element data = doc[param_name] prefix_parts = [ - f"{data['humanName']}", - ] + f"{data['humanName']}", + ] prefix_parts += data["documentation"] for key, value in data["fields"].items(): prefix_parts.append(f"{key}: {value}") prefix_parts += format_columns(data["values"]) doc_text = "\n# ".join(prefix_parts) if param_name in param_default_dict: - default_value = format(param_default_dict[param_name].value, '.6f').rstrip('0').rstrip('.') + default_value = format(param_default_dict[param_name].value, ".6f").rstrip("0").rstrip(".") doc_text += f"\n# Default: {default_value}" if not is_first_param_in_file: new_lines.append("\n") @@ -655,15 +680,15 @@ def update_parameter_documentation_file(doc, sort_type, param_default_dict, para is_first_param_in_file = False if total_params == documented_params: - logging.info("Read file %s with %d parameters, all got documented", - param_file, total_params) + logging.info("Read file %s with %d parameters, all got documented", param_file, total_params) else: - logging.warning("Read file %s with %d parameters, but only %s of which got documented", - param_file, total_params, documented_params) + logging.warning( + "Read file %s with %d parameters, but only %s of which got documented", param_file, total_params, documented_params + ) logging.warning("No documentation found for: %s", ", ".join(undocumented_params)) # Write the new file contents to the file - with open(param_file, "w", encoding="utf-8", newline='\n') as file: # Ensure newline character is LF, even on windows + with open(param_file, "w", encoding="utf-8", newline="\n") as file: # Ensure newline character is LF, even on windows file.writelines(new_lines) @@ -676,7 +701,7 @@ def print_read_only_params(doc): """ logging.info("ReadOnly parameters:") for param_name, param_value in doc.items(): - if 'ReadOnly' in param_value['fields'] and param_value['fields']['ReadOnly']: + if "ReadOnly" in param_value["fields"] and param_value["fields"]["ReadOnly"]: logging.info(param_name) @@ -692,10 +717,10 @@ def get_xml_url(vehicle_type: str, firmware_version: str) -> str: "ArduSub": "versioned/Sub/stable-", "AntennaTracker": "versioned/Tracker/stable-", # Not yet versioned in the https://autotest.ardupilot.org/Parameters server - 'AP_Periph': 'versioned/Periph/stable-', - 'Blimp': 'versioned/Blimp/stable-', - 'Heli': 'versioned/Copter/stable-', - 'SITL': 'versioned/SITL/stable-' + "AP_Periph": "versioned/Periph/stable-", + "Blimp": "versioned/Blimp/stable-", + "Heli": "versioned/Copter/stable-", + "SITL": "versioned/SITL/stable-", } try: vehicle_subdir = vehicle_parm_subdir[vehicle_type] + firmware_version @@ -708,8 +733,10 @@ def get_xml_url(vehicle_type: str, firmware_version: str) -> str: xml_url = BASE_URL + vehicle_type + "/" return xml_url -def parse_parameter_metadata(xml_url: str, xml_dir: str, xml_file: str, - vehicle_type: str, max_line_length: int) -> Dict[str, Any]: + +def parse_parameter_metadata( + xml_url: str, xml_dir: str, xml_file: str, vehicle_type: str, max_line_length: int +) -> Dict[str, Any]: xml_root = get_xml_data(xml_url, xml_dir, xml_file, vehicle_type) return create_doc_dict(xml_root, vehicle_type, max_line_length) @@ -720,27 +747,29 @@ def main(): xml_url = get_xml_url(args.vehicle_type, args.firmware_version) xml_dir = get_xml_dir(args.target) - doc_dict = parse_parameter_metadata(xml_url, xml_dir, PARAM_DEFINITION_XML_FILE, - args.vehicle_type, args.max_line_length) + doc_dict = parse_parameter_metadata( + xml_url, xml_dir, PARAM_DEFINITION_XML_FILE, args.vehicle_type, args.max_line_length + ) param_default_dict = load_default_param_file(xml_dir) - update_parameter_documentation(doc_dict, args.target, args.sort, param_default_dict, - args.delete_documentation_annotations) + update_parameter_documentation( + doc_dict, args.target, args.sort, param_default_dict, args.delete_documentation_annotations + ) if args.verbose: print_read_only_params(doc_dict) # Annotate lua MAGfit XML documentation into the respective parameter file xml_file = LUA_PARAM_DEFINITION_XML_FILE if os_path.isfile(os_path.join(os_path.dirname(args.target), xml_file)): - doc_dict = parse_parameter_metadata(xml_url, xml_dir, xml_file, - args.vehicle_type, args.max_line_length) + doc_dict = parse_parameter_metadata(xml_url, xml_dir, xml_file, args.vehicle_type, args.max_line_length) target = os_path.join(os_path.dirname(args.target), "24_inflight_magnetometer_fit_setup.param") param_default_dict = load_default_param_file(xml_dir) - update_parameter_documentation(doc_dict, target, args.sort, param_default_dict, - args.delete_documentation_annotations) + update_parameter_documentation( + doc_dict, target, args.sort, param_default_dict, args.delete_documentation_annotations + ) else: logging.warning("No LUA MAGfit XML documentation found, skipping annotation of %s", target) - except (IOError, OSError, SystemExit) as exp: + except (IOError, OSError, SystemExit) as exp: logging.fatal(exp) sys_exit(1) diff --git a/MethodicConfigurator/ardupilot_methodic_configurator.py b/MethodicConfigurator/ardupilot_methodic_configurator.py index 2b45a54..bdd005e 100755 --- a/MethodicConfigurator/ardupilot_methodic_configurator.py +++ b/MethodicConfigurator/ardupilot_methodic_configurator.py @@ -1,41 +1,33 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" import argparse from logging import basicConfig as logging_basicConfig -from logging import getLevelName as logging_getLevelName from logging import debug as logging_debug -from logging import info as logging_info -#from logging import warning as logging_warning + +# from logging import warning as logging_warning from logging import error as logging_error +from logging import getLevelName as logging_getLevelName +from logging import info as logging_info from sys import exit as sys_exit from MethodicConfigurator.backend_filesystem import LocalFilesystem from MethodicConfigurator.backend_flightcontroller import FlightController - +from MethodicConfigurator.common_arguments import add_common_arguments_and_parse from MethodicConfigurator.frontend_tkinter_base import show_error_message - +from MethodicConfigurator.frontend_tkinter_component_editor import ComponentEditorWindow from MethodicConfigurator.frontend_tkinter_connection_selection import ConnectionSelectionWindow - -from MethodicConfigurator.frontend_tkinter_flightcontroller_info import FlightControllerInfoWindow - from MethodicConfigurator.frontend_tkinter_directory_selection import VehicleDirectorySelectionWindow - -from MethodicConfigurator.frontend_tkinter_component_editor import ComponentEditorWindow - +from MethodicConfigurator.frontend_tkinter_flightcontroller_info import FlightControllerInfoWindow from MethodicConfigurator.frontend_tkinter_parameter_editor import ParameterEditorWindow - -from MethodicConfigurator.common_arguments import add_common_arguments_and_parse - -from MethodicConfigurator.internationalization import _, load_translation - +from MethodicConfigurator import _ from MethodicConfigurator.version import VERSION @@ -48,16 +40,20 @@ def argument_parser(): Returns: argparse.Namespace: An object containing the parsed arguments. """ - parser = argparse.ArgumentParser(description=_('ArduPilot methodic configurator is a simple GUI with a table that lists ' - 'parameters. The GUI reads intermediate parameter files from a directory and ' - 'displays their parameters in a table. Each row displays the parameter name, ' - 'its current value on the flight controller, its new value from the selected ' - 'intermediate parameter file, and an "Upload" checkbox. The GUI includes "Upload ' - 'selected params to FC" and "Skip" buttons at the bottom. ' - 'When "Upload Selected to FC" is clicked, it uploads the selected parameters to the ' - 'flight controller. ' - 'When "Skip" is pressed, it skips to the next intermediate parameter file. ' - 'The process gets repeated for each intermediate parameter file.')) + parser = argparse.ArgumentParser( + description=_( + "ArduPilot methodic configurator is a simple GUI with a table that lists " + "parameters. The GUI reads intermediate parameter files from a directory and " + "displays their parameters in a table. Each row displays the parameter name, " + "its current value on the flight controller, its new value from the selected " + 'intermediate parameter file, and an "Upload" checkbox. The GUI includes "Upload ' + 'selected params to FC" and "Skip" buttons at the bottom. ' + 'When "Upload Selected to FC" is clicked, it uploads the selected parameters to the ' + "flight controller. " + 'When "Skip" is pressed, it skips to the next intermediate parameter file. ' + "The process gets repeated for each intermediate parameter file." + ) + ) parser = FlightController.add_argparse_arguments(parser) parser = LocalFilesystem.add_argparse_arguments(parser) parser = ComponentEditorWindow.add_argparse_arguments(parser) @@ -83,33 +79,33 @@ def connect_to_fc_and_read_parameters(args): else: logging_info(_("Vehicle type explicitly set to %s."), vehicle_type) - return flight_controller,vehicle_type + return flight_controller, vehicle_type def component_editor(args, flight_controller, vehicle_type, local_filesystem, vehicle_dir_window): component_editor_window = ComponentEditorWindow(VERSION, local_filesystem) - if vehicle_dir_window and \ - vehicle_dir_window.configuration_template is not None and \ - vehicle_dir_window.use_fc_params.get() and \ - flight_controller.fc_parameters: + if ( + vehicle_dir_window + and vehicle_dir_window.configuration_template is not None + and vehicle_dir_window.use_fc_params.get() + and flight_controller.fc_parameters + ): # copy vehicle parameters to component editor values component_editor_window.set_values_from_fc_parameters(flight_controller.fc_parameters, local_filesystem.doc_dict) component_editor_window.populate_frames() component_editor_window.set_vehicle_type_and_version(vehicle_type, flight_controller.info.flight_sw_version_and_type) component_editor_window.set_fc_manufacturer(flight_controller.info.vendor) component_editor_window.set_fc_model(flight_controller.info.product) - if vehicle_dir_window and \ - vehicle_dir_window.configuration_template is not None: + if vehicle_dir_window and vehicle_dir_window.configuration_template is not None: component_editor_window.set_vehicle_configuration_template(vehicle_dir_window.configuration_template) if args.skip_component_editor: component_editor_window.root.after(10, component_editor_window.root.destroy) component_editor_window.root.mainloop() - if vehicle_dir_window and \ - vehicle_dir_window.configuration_template is not None and \ - vehicle_dir_window.use_fc_params.get(): + if vehicle_dir_window and vehicle_dir_window.configuration_template is not None and vehicle_dir_window.use_fc_params.get(): error_message = local_filesystem.copy_fc_params_values_to_template_created_vehicle_files( - flight_controller.fc_parameters) + flight_controller.fc_parameters + ) if error_message: logging_error(error_message) show_error_message(_("Error in derived parameters"), error_message) @@ -117,25 +113,22 @@ def component_editor(args, flight_controller, vehicle_type, local_filesystem, ve def main(): - # modify the global _() function - global _ # pylint: disable=global-statement - - _ = load_translation() # done as soon as possible so that the correct language is used args = argument_parser() - logging_basicConfig(level=logging_getLevelName(args.loglevel), format='%(asctime)s - %(levelname)s - %(message)s') + logging_basicConfig(level=logging_getLevelName(args.loglevel), format="%(asctime)s - %(levelname)s - %(message)s") # Connect to the flight controller and read the parameters flight_controller, vehicle_type = connect_to_fc_and_read_parameters(args) param_default_values = {} - if flight_controller.master is not None or args.device == 'test': + if flight_controller.master is not None or args.device == "test": fciw = FlightControllerInfoWindow(flight_controller) param_default_values = fciw.get_param_default_values() try: - local_filesystem = LocalFilesystem(args.vehicle_dir, vehicle_type, flight_controller.info.flight_sw_version, - args.allow_editing_template_files) + local_filesystem = LocalFilesystem( + args.vehicle_dir, vehicle_type, flight_controller.info.flight_sw_version, args.allow_editing_template_files + ) except SystemExit as exp: show_error_message(_("Fatal error reading parameter files"), f"{exp}") raise @@ -158,7 +151,7 @@ def main(): if param_default_values_dirty: local_filesystem.write_param_default_values_to_file(param_default_values) - imu_tcal_available = 'INS_TCAL1_ENABLE' in flight_controller.fc_parameters or not flight_controller.fc_parameters + imu_tcal_available = "INS_TCAL1_ENABLE" in flight_controller.fc_parameters or not flight_controller.fc_parameters start_file = local_filesystem.get_start_file(args.n, imu_tcal_available) # Call the GUI function with the starting intermediate parameter file diff --git a/MethodicConfigurator/argparse_check_range.py b/MethodicConfigurator/argparse_check_range.py index e58908e..105f469 100644 --- a/MethodicConfigurator/argparse_check_range.py +++ b/MethodicConfigurator/argparse_check_range.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Dmitriy Kovalev @@ -8,24 +8,20 @@ SPDX-License-Identifier: Apache-2.0 https://gist.github.com/dmitriykovalev/2ab1aa33a8099ef2d514925d84aa89e7 -''' +""" + +from argparse import Action, ArgumentError +from operator import ge, gt, le, lt + +from MethodicConfigurator import _ -from argparse import Action -from argparse import ArgumentError -from operator import gt -from operator import ge -from operator import lt -from operator import le -from MethodicConfigurator.internationalization import _ class CheckRange(Action): - ''' + """ Check if the Argparse argument value is within the specified range - ''' - ops = {"inf": gt, - "min": ge, - "sup": lt, - "max": le} + """ + + ops = {"inf": gt, "min": ge, "sup": lt, "max": le} def __init__(self, *args, **kwargs): if "min" in kwargs and "inf" in kwargs: diff --git a/MethodicConfigurator/backend_filesystem.py b/MethodicConfigurator/backend_filesystem.py index 7352c04..923e44f 100644 --- a/MethodicConfigurator/backend_filesystem.py +++ b/MethodicConfigurator/backend_filesystem.py @@ -1,53 +1,46 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" -from os import path as os_path +# from sys import exit as sys_exit +from logging import debug as logging_debug +from logging import error as logging_error +from logging import info as logging_info +from logging import warning as logging_warning from os import getcwd as os_getcwd from os import listdir as os_listdir +from os import path as os_path from os import rename as os_rename - from platform import system as platform_system - +from re import compile as re_compile from shutil import copy2 as shutil_copy2 from shutil import copytree as shutil_copytree - -from re import compile as re_compile - -# from sys import exit as sys_exit -from logging import debug as logging_debug -from logging import info as logging_info -from logging import warning as logging_warning -from logging import error as logging_error - -from typing import Dict -from typing import List -from typing import Tuple - +from typing import Dict, List, Tuple from zipfile import ZipFile from requests import get as requests_get -from MethodicConfigurator.annotate_params import PARAM_DEFINITION_XML_FILE, Par -from MethodicConfigurator.annotate_params import get_xml_url -from MethodicConfigurator.annotate_params import get_xml_dir -from MethodicConfigurator.annotate_params import load_default_param_file -from MethodicConfigurator.annotate_params import parse_parameter_metadata -from MethodicConfigurator.annotate_params import format_columns -from MethodicConfigurator.annotate_params import split_into_lines -from MethodicConfigurator.annotate_params import update_parameter_documentation - -from MethodicConfigurator.backend_filesystem_vehicle_components import VehicleComponents +from MethodicConfigurator.annotate_params import ( + PARAM_DEFINITION_XML_FILE, + Par, + format_columns, + get_xml_dir, + get_xml_url, + load_default_param_file, + parse_parameter_metadata, + split_into_lines, + update_parameter_documentation, +) from MethodicConfigurator.backend_filesystem_configuration_steps import ConfigurationSteps from MethodicConfigurator.backend_filesystem_program_settings import ProgramSettings - -from MethodicConfigurator.internationalization import _ +from MethodicConfigurator.backend_filesystem_vehicle_components import VehicleComponents +from MethodicConfigurator import _ TOOLTIP_MAX_LENGTH = 105 @@ -87,6 +80,7 @@ class LocalFilesystem(VehicleComponents, ConfigurationSteps, ProgramSettings): param_default_dict (dict): A dictionary of default parameter values. doc_dict (dict): A dictionary containing documentation for each parameter. """ + def __init__(self, vehicle_dir: str, vehicle_type: str, fw_version: str, allow_editing_template_files: bool): self.file_parameters = None VehicleComponents.__init__(self) @@ -124,21 +118,19 @@ def re_init(self, vehicle_dir: str, vehicle_type: str): # Read intermediate parameters from files self.file_parameters = self.read_params_from_files() if not self.file_parameters: - return # No files intermediate parameters files found, no need to continue, the rest needs them + return # No files intermediate parameters files found, no need to continue, the rest needs them # Read ArduPilot parameter documentation xml_url = get_xml_url(vehicle_type, self.fw_version) xml_dir = get_xml_dir(vehicle_dir) - self.doc_dict = parse_parameter_metadata(xml_url, xml_dir, PARAM_DEFINITION_XML_FILE, - vehicle_type, TOOLTIP_MAX_LENGTH) + self.doc_dict = parse_parameter_metadata(xml_url, xml_dir, PARAM_DEFINITION_XML_FILE, vehicle_type, TOOLTIP_MAX_LENGTH) self.param_default_dict = load_default_param_file(xml_dir) # Extend parameter documentation metadata if .pdef.xml exists for filename in self.file_parameters: pdef_xml_file = filename.replace(".param", ".pdef.xml") if os_path.exists(os_path.join(xml_dir, pdef_xml_file)): - doc_dict = parse_parameter_metadata("", xml_dir, pdef_xml_file, - vehicle_type, TOOLTIP_MAX_LENGTH) + doc_dict = parse_parameter_metadata("", xml_dir, pdef_xml_file, vehicle_type, TOOLTIP_MAX_LENGTH) self.doc_dict.update(doc_dict) self.__extend_and_reformat_parameter_documentation_metadata() @@ -146,11 +138,12 @@ def re_init(self, vehicle_dir: str, vehicle_type: str): def vehicle_configuration_files_exist(self, vehicle_dir: str) -> bool: if os_path.exists(vehicle_dir) and os_path.isdir(vehicle_dir): vehicle_configuration_files = os_listdir(vehicle_dir) - if platform_system() == 'Windows': + if platform_system() == "Windows": vehicle_configuration_files = [f.lower() for f in vehicle_configuration_files] - pattern = re_compile(r'^\d{2}_.*\.param$') - if self.vehicle_components_json_filename in vehicle_configuration_files and \ - any(pattern.match(f) for f in vehicle_configuration_files): + pattern = re_compile(r"^\d{2}_.*\.param$") + if self.vehicle_components_json_filename in vehicle_configuration_files and any( + pattern.match(f) for f in vehicle_configuration_files + ): return True return False @@ -158,8 +151,8 @@ def rename_parameter_files(self): # Rename parameter files if some new files got added to the vehicle directory if self.vehicle_dir is not None and self.configuration_steps is not None: for new_filename in self.configuration_steps: - if 'old_filenames' in self.configuration_steps[new_filename]: - for old_filename in self.configuration_steps[new_filename]['old_filenames']: + if "old_filenames" in self.configuration_steps[new_filename]: + for old_filename in self.configuration_steps[new_filename]["old_filenames"]: if self.vehicle_configuration_file_exists(old_filename) and old_filename != new_filename: new_filename_path = os_path.join(self.vehicle_dir, new_filename) old_filename_path = os_path.join(self.vehicle_dir, old_filename) @@ -168,34 +161,34 @@ def rename_parameter_files(self): def __extend_and_reformat_parameter_documentation_metadata(self): # pylint: disable=too-many-branches for param_name, param_info in self.doc_dict.items(): - if 'fields' in param_info: - param_fields = param_info['fields'] - if 'Units' in param_fields: - units_list = param_fields['Units'].split('(') - param_info['unit'] = units_list[0].strip() + if "fields" in param_info: + param_fields = param_info["fields"] + if "Units" in param_fields: + units_list = param_fields["Units"].split("(") + param_info["unit"] = units_list[0].strip() if len(units_list) > 1: - param_info['unit_tooltip'] = units_list[1].strip(')').strip() - if 'Range' in param_fields: - param_info['min'] = float(param_fields['Range'].split(' ')[0].strip()) - param_info['max'] = float(param_fields['Range'].split(' ')[1].strip()) - if 'Calibration' in param_fields: - param_info['Calibration'] = self.str_to_bool(param_fields['Calibration'].strip()) - if 'ReadOnly' in param_fields: - param_info['ReadOnly'] = self.str_to_bool(param_fields['ReadOnly'].strip()) - if 'RebootRequired' in param_fields: - param_info['RebootRequired'] = self.str_to_bool(param_fields['RebootRequired'].strip()) - if 'Bitmask' in param_fields: - bitmask_items = param_fields['Bitmask'].split(',') - param_info['Bitmask'] = {} + param_info["unit_tooltip"] = units_list[1].strip(")").strip() + if "Range" in param_fields: + param_info["min"] = float(param_fields["Range"].split(" ")[0].strip()) + param_info["max"] = float(param_fields["Range"].split(" ")[1].strip()) + if "Calibration" in param_fields: + param_info["Calibration"] = self.str_to_bool(param_fields["Calibration"].strip()) + if "ReadOnly" in param_fields: + param_info["ReadOnly"] = self.str_to_bool(param_fields["ReadOnly"].strip()) + if "RebootRequired" in param_fields: + param_info["RebootRequired"] = self.str_to_bool(param_fields["RebootRequired"].strip()) + if "Bitmask" in param_fields: + bitmask_items = param_fields["Bitmask"].split(",") + param_info["Bitmask"] = {} for item in bitmask_items: - key, value = item.split(':') - param_info['Bitmask'][int(key.strip())] = value.strip() + key, value = item.split(":") + param_info["Bitmask"][int(key.strip())] = value.strip() - if 'values' in param_info and param_info['values']: + if param_info.get("values"): try: - param_info['Values'] = {int(k): v for k, v in param_info['values'].items()} + param_info["Values"] = {int(k): v for k, v in param_info["values"].items()} except ValueError: - param_info['Values'] = {float(k): v for k, v in param_info['values'].items()} + param_info["Values"] = {float(k): v for k, v in param_info["values"].items()} # print(param_info['Values']) prefix_parts = [ @@ -203,13 +196,13 @@ def __extend_and_reformat_parameter_documentation_metadata(self): # pylint: dis ] prefix_parts += param_info["documentation"] for key, value in param_info["fields"].items(): - if key not in ['Units', 'UnitText']: + if key not in ["Units", "UnitText"]: prefix_parts += split_into_lines(f"{key}: {value}", TOOLTIP_MAX_LENGTH) prefix_parts += format_columns(param_info["values"], TOOLTIP_MAX_LENGTH) if param_name in self.param_default_dict: - default_value = format(self.param_default_dict[param_name].value, '.6f').rstrip('0').rstrip('.') + default_value = format(self.param_default_dict[param_name].value, ".6f").rstrip("0").rstrip(".") prefix_parts += [f"Default: {default_value}"] - param_info['doc_tooltip'] = ('\n').join(prefix_parts) + param_info["doc_tooltip"] = ("\n").join(prefix_parts) def read_params_from_files(self): """ @@ -226,11 +219,11 @@ def read_params_from_files(self): parameters = {} 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$') + pattern = re_compile(r"^\d{2}_.*\.param$") for filename in sorted(os_listdir(self.vehicle_dir)): if pattern.match(filename): - if filename in ['00_default.param', '01_ignore_readonly.param']: + 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)) else: @@ -257,7 +250,7 @@ def str_to_bool(s): 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: Dict[str, "Par"], filename_out: str, annotate_doc: bool = True) -> None: """ Exports a dictionary of parameters to a .param file and optionally annotates the documentation. @@ -271,10 +264,9 @@ def export_to_param(self, params: Dict[str, 'Par'], filename_out: str, annotate_ """ Par.export_to_param(Par.format_params(params), 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) + update_parameter_documentation( + self.doc_dict, os_path.join(self.vehicle_dir, filename_out), "missionplanner", self.param_default_dict + ) def vehicle_configuration_file_exists(self, filename: str) -> bool: """ @@ -286,8 +278,9 @@ def vehicle_configuration_file_exists(self, filename: str) -> bool: Returns: - bool: True if the file exists and is a file (not a directory), False otherwise. """ - return os_path.exists(os_path.join(self.vehicle_dir, filename)) and \ - os_path.isfile(os_path.join(self.vehicle_dir, filename)) + return os_path.exists(os_path.join(self.vehicle_dir, filename)) and os_path.isfile( + os_path.join(self.vehicle_dir, filename) + ) def __all_intermediate_parameter_file_comments(self) -> Dict[str, str]: """ @@ -301,13 +294,13 @@ def __all_intermediate_parameter_file_comments(self) -> Dict[str, str]: - Dict[str, str]: A dictionary mapping parameter names to their comments. """ ret = {} - for _filename, params in self.file_parameters.items(): + for params in self.file_parameters.values(): for param, info in params.items(): if info.comment: 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]) -> Dict[str, "Par"]: """ Annotates comments from intermediate parameter files to a parameter value-only dictionary. @@ -324,10 +317,10 @@ def annotate_intermediate_comments_to_param_dict(self, param_dict: Dict[str, flo 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, '')) + ret[param] = Par(float(value), ip_comments.get(param, "")) return ret - def categorize_parameters(self, param: Dict[str, 'Par']) -> List[Dict[str, 'Par']]: + def categorize_parameters(self, param: Dict[str, "Par"]) -> List[Dict[str, "Par"]]: """ Categorize parameters into three categories based on their default values and documentation attributes. @@ -347,15 +340,16 @@ def categorize_parameters(self, param: Dict[str, 'Par']) -> List[Dict[str, 'Par' 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.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): + 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): + 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 @@ -402,7 +396,7 @@ def zip_files(self, files_to_zip: List[Tuple[bool, str]]): indicating if the file was written and a string for the filename. """ zip_file_path = self.zip_file_path() - with ZipFile(zip_file_path, 'w') as zipf: + with ZipFile(zip_file_path, "w") as zipf: # Add all intermediate parameter files for file_name in self.file_parameters: zipf.write(os_path.join(self.vehicle_dir, file_name), arcname=file_name) @@ -411,9 +405,16 @@ def zip_files(self, files_to_zip: List[Tuple[bool, str]]): self.add_configuration_file_to_zip(zipf, pdef_xml_file) # Check for and add specific files if they exist - specific_files = ["00_default.param", "apm.pdef.xml", self.configuration_steps_filename, - self.vehicle_components_json_filename, "vehicle.jpg", "last_uploaded_filename.txt", - "tempcal_gyro.png", "tempcal_acc.png"] + specific_files = [ + "00_default.param", + "apm.pdef.xml", + self.configuration_steps_filename, + self.vehicle_components_json_filename, + "vehicle.jpg", + "last_uploaded_filename.txt", + "tempcal_gyro.png", + "tempcal_acc.png", + ] for file_name in specific_files: self.add_configuration_file_to_zip(zipf, file_name) @@ -424,12 +425,11 @@ def zip_files(self, files_to_zip: List[Tuple[bool, str]]): logging_info(_("Intermediate parameter files and summary files zipped to %s"), zip_file_path) def vehicle_image_filepath(self): - return os_path.join(self.vehicle_dir, 'vehicle.jpg') + return os_path.join(self.vehicle_dir, "vehicle.jpg") def vehicle_image_exists(self): return os_path.exists(self.vehicle_image_filepath()) and os_path.isfile(self.vehicle_image_filepath()) - @staticmethod def new_vehicle_dir(base_dir: str, new_dir: str): return os_path.join(base_dir, new_dir) @@ -441,7 +441,7 @@ def directory_exists(directory: str) -> bool: def copy_template_files_to_new_vehicle_dir(self, template_dir: str, new_vehicle_dir: str): # Copy the template files to the new vehicle directory for item in os_listdir(template_dir): - if item in ['apm.pdef.xml', 'vehicle.jpg', 'last_uploaded_filename.txt', 'tempcal_acc.png', 'tempcal_gyro.png']: + if item in ["apm.pdef.xml", "vehicle.jpg", "last_uploaded_filename.txt", "tempcal_acc.png", "tempcal_gyro.png"]: continue s = os_path.join(template_dir, item) d = os_path.join(new_vehicle_dir, item) @@ -471,14 +471,14 @@ def copy_fc_values_to_file(self, selected_file: str, params: Dict[str, float]): def write_last_uploaded_filename(self, current_file: str): try: - with open(os_path.join(self.vehicle_dir, 'last_uploaded_filename.txt'), 'w', encoding='utf-8') as file: + with open(os_path.join(self.vehicle_dir, "last_uploaded_filename.txt"), "w", encoding="utf-8") as file: file.write(current_file) except Exception as e: # pylint: disable=broad-except logging_error(_("Error writing last uploaded filename: %s"), e) def __read_last_uploaded_filename(self) -> str: try: - with open(os_path.join(self.vehicle_dir, 'last_uploaded_filename.txt'), 'r', encoding='utf-8') as file: + with open(os_path.join(self.vehicle_dir, "last_uploaded_filename.txt"), "r", encoding="utf-8") as file: return file.read().strip() except FileNotFoundError as e: logging_debug(_("last_uploaded_filename.txt not found: %s"), e) @@ -495,11 +495,14 @@ def get_start_file(self, explicit_index: int, tcal_available: bool) -> str: return "" # Determine the starting file based on the --n command line argument - start_file_index = explicit_index # Ensure the index is within the range of available files + start_file_index = explicit_index # Ensure the index is within the range of available files if start_file_index >= len(files): start_file_index = len(files) - 1 - logging_warning(_("Starting file index %s is out of range. Starting with file %s instead."), - explicit_index, files[start_file_index]) + logging_warning( + _("Starting file index %s is out of range. Starting with file %s instead."), + explicit_index, + files[start_file_index], + ) return files[start_file_index] if tcal_available: @@ -533,14 +536,13 @@ def get_start_file(self, explicit_index: int, tcal_available: bool) -> str: def get_eval_variables(self): variables = {} - if hasattr(self, 'vehicle_components') and self.vehicle_components and \ - 'Components' in self.vehicle_components: - variables['vehicle_components'] = self.vehicle_components['Components'] - if hasattr(self, 'doc_dict') and self.doc_dict: - variables['doc_dict'] = self.doc_dict + if hasattr(self, "vehicle_components") and self.vehicle_components and "Components" in self.vehicle_components: + variables["vehicle_components"] = self.vehicle_components["Components"] + if hasattr(self, "doc_dict") and self.doc_dict: + variables["doc_dict"] = self.doc_dict return variables - def copy_fc_params_values_to_template_created_vehicle_files(self, fc_parameters: Dict[str, 'Par']): + def copy_fc_params_values_to_template_created_vehicle_files(self, fc_parameters: Dict[str, "Par"]): eval_variables = self.get_eval_variables() for param_filename, param_dict in self.file_parameters.items(): for param_name, param in param_dict.items(): @@ -548,48 +550,52 @@ def copy_fc_params_values_to_template_created_vehicle_files(self, fc_parameters: param.value = fc_parameters[param_name] if self.configuration_steps and param_filename in self.configuration_steps: step_dict = self.configuration_steps[param_filename] - error_msg = self.compute_parameters(param_filename, step_dict, 'forced', eval_variables) + error_msg = self.compute_parameters(param_filename, step_dict, "forced", eval_variables) if error_msg: return error_msg - error_msg = self.compute_parameters(param_filename, step_dict, 'derived', eval_variables) + error_msg = self.compute_parameters(param_filename, step_dict, "derived", eval_variables) if error_msg: return error_msg Par.export_to_param(Par.format_params(param_dict), os_path.join(self.vehicle_dir, param_filename)) - return '' + return "" - def write_param_default_values(self, param_default_values: Dict[str, 'Par']) -> bool: + def write_param_default_values(self, param_default_values: Dict[str, "Par"]) -> bool: param_default_values = 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'): + def write_param_default_values_to_file(self, param_default_values: Dict[str, "Par"], filename: str = "00_default.param"): 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)) def get_download_url_and_local_filename(self, selected_file: str) -> Tuple[str, str]: if selected_file in self.configuration_steps: - if 'download_file' in self.configuration_steps[selected_file] and \ - self.configuration_steps[selected_file]['download_file']: - src = self.configuration_steps[selected_file]['download_file'].get('source_url', '') - dst = self.configuration_steps[selected_file]['download_file'].get('dest_local', '') + if ( + "download_file" in self.configuration_steps[selected_file] + and self.configuration_steps[selected_file]["download_file"] + ): + src = self.configuration_steps[selected_file]["download_file"].get("source_url", "") + dst = self.configuration_steps[selected_file]["download_file"].get("dest_local", "") if self.vehicle_dir and src and dst: return src, os_path.join(self.vehicle_dir, dst) - return '', '' + return "", "" def get_upload_local_and_remote_filenames(self, selected_file: str) -> Tuple[str, str]: if selected_file in self.configuration_steps: - if 'upload_file' in self.configuration_steps[selected_file] and \ - self.configuration_steps[selected_file]['upload_file']: - src = self.configuration_steps[selected_file]['upload_file'].get('source_local', '') - dst = self.configuration_steps[selected_file]['upload_file'].get('dest_on_fc', '') + if ( + "upload_file" in self.configuration_steps[selected_file] + and self.configuration_steps[selected_file]["upload_file"] + ): + src = self.configuration_steps[selected_file]["upload_file"].get("source_local", "") + dst = self.configuration_steps[selected_file]["upload_file"].get("dest_on_fc", "") if self.vehicle_dir and src and dst: return os_path.join(self.vehicle_dir, src), dst - return '', '' + return "", "" @staticmethod - def download_file_from_url(url: str, local_filename: str, timeout: int=5) -> bool: + def download_file_from_url(url: str, local_filename: str, timeout: int = 5) -> bool: if not url or not local_filename: logging_error(_("URL or local filename not provided.")) return False @@ -606,23 +612,39 @@ def download_file_from_url(url: str, local_filename: str, timeout: int=5) -> boo @staticmethod def add_argparse_arguments(parser): - parser.add_argument('-t', '--vehicle-type', - choices=VehicleComponents.supported_vehicles(), - default='', - help=_('The type of the vehicle. Defaults to ArduCopter')) - parser.add_argument('--vehicle-dir', - type=str, - default=os_getcwd(), - help=_('Directory containing vehicle-specific intermediate parameter files. ' - 'Defaults to the current working directory')) - parser.add_argument('--n', - type=int, - default=-1, - help=_('Start directly on the nth intermediate parameter file (skips previous files). ' - 'Default is to start on the file next to the last that you wrote to the flight controller.' - 'If the file does not exist, it will start on the first file.')) - parser.add_argument('--allow-editing-template-files', - action='store_true', - help=_('Allow opening and editing template files directly. ' - 'Only for software developers that know what they are doing.')) + parser.add_argument( + "-t", + "--vehicle-type", + choices=VehicleComponents.supported_vehicles(), + default="", + help=_("The type of the vehicle. Defaults to ArduCopter"), + ) + parser.add_argument( + "--vehicle-dir", + type=str, + default=os_getcwd(), + help=_( + "Directory containing vehicle-specific intermediate parameter files. " + "Defaults to the current working directory" + ), + ) + parser.add_argument( + "--n", + type=int, + default=-1, + help=_( + "Start directly on the nth intermediate parameter file (skips previous files). " + "Default is to start on the file next to the last that you wrote to the flight controller." + "If the file does not exist, it will start on the first file." + ), + ) + parser.add_argument( + "--allow-editing-template-files", + action="store_true", + help=_( + "Allow opening and editing template files directly. " + "Only for software developers that know what they are doing." + "Defaults to %(default)s" + ), + ) return parser diff --git a/MethodicConfigurator/backend_filesystem_configuration_steps.py b/MethodicConfigurator/backend_filesystem_configuration_steps.py index f5ae577..3b1c853 100644 --- a/MethodicConfigurator/backend_filesystem_configuration_steps.py +++ b/MethodicConfigurator/backend_filesystem_configuration_steps.py @@ -1,28 +1,26 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" -from os import path as os_path +from json import JSONDecodeError +from json import load as json_load +from logging import error as logging_error # from sys import exit as sys_exit # from logging import debug as logging_debug from logging import info as logging_info from logging import warning as logging_warning -from logging import error as logging_error - -from json import load as json_load -from json import JSONDecodeError +from os import path as os_path from typing import Tuple from MethodicConfigurator.annotate_params import Par - -from MethodicConfigurator.internationalization import _ +from MethodicConfigurator import _ class ConfigurationSteps: @@ -36,6 +34,7 @@ class ConfigurationSteps: configuration_steps_filename (str): The name of the file containing documentation for the configuration files. configuration_steps (dict): A dictionary containing the configuration steps. """ + def __init__(self, _vehicle_dir: str, vehicle_type: str): self.configuration_steps_filename = "configuration_steps_" + vehicle_type + ".json" self.configuration_steps = {} @@ -44,7 +43,7 @@ def __init__(self, _vehicle_dir: str, vehicle_type: str): self.log_loaded_file = False def re_init(self, vehicle_dir: str, vehicle_type: str): - if vehicle_type == '': + if vehicle_type == "": return self.configuration_steps_filename = "configuration_steps_" + vehicle_type + ".json" # Define a list of directories to search for the configuration_steps_filename file @@ -52,17 +51,20 @@ def re_init(self, vehicle_dir: str, vehicle_type: str): file_found = False for i, directory in enumerate(search_directories): try: - with open(os_path.join(directory, self.configuration_steps_filename), 'r', encoding='utf-8') as file: + with open(os_path.join(directory, self.configuration_steps_filename), "r", encoding="utf-8") as file: self.configuration_steps = json_load(file) file_found = True if self.log_loaded_file: if i == 0: - logging_warning(_("Configuration steps '%s' loaded from %s " \ - "(overwriting default configuration steps)."), - self.configuration_steps_filename, directory) + logging_warning( + _("Configuration steps '%s' loaded from %s (overwriting default configuration steps)."), + self.configuration_steps_filename, + directory, + ) if i == 1: - logging_info(_("Configuration steps '%s' loaded from %s."), - self.configuration_steps_filename, directory) + logging_info( + _("Configuration steps '%s' loaded from %s."), self.configuration_steps_filename, directory + ) break except FileNotFoundError: pass @@ -71,8 +73,8 @@ def re_init(self, vehicle_dir: str, vehicle_type: str): break if file_found: for filename, file_info in self.configuration_steps.items(): - self.__validate_parameters_in_configuration_steps(filename, file_info, 'forced') - self.__validate_parameters_in_configuration_steps(filename, file_info, 'derived') + self.__validate_parameters_in_configuration_steps(filename, file_info, "forced") + self.__validate_parameters_in_configuration_steps(filename, file_info, "derived") else: logging_warning(_("No configuration steps documentation and no forced and derived parameters will be available.")) self.log_loaded_file = True @@ -84,20 +86,32 @@ def __validate_parameters_in_configuration_steps(self, filename: str, file_info: This method checks if the parameters in the configuration steps are correctly formatted. If a parameter is missing the 'New Value' or 'Change Reason' attribute, an error message is logged. """ - if parameter_type + '_parameters' in file_info: - if not isinstance(file_info[parameter_type + '_parameters'], dict): - logging_error(_("Error in file '%s': '%s' %s parameter is not a dictionary"), - self.configuration_steps_filename, filename, parameter_type) + if parameter_type + "_parameters" in file_info: + if not isinstance(file_info[parameter_type + "_parameters"], dict): + logging_error( + _("Error in file '%s': '%s' %s parameter is not a dictionary"), + self.configuration_steps_filename, + filename, + parameter_type, + ) return - for parameter, parameter_info in file_info[parameter_type + '_parameters'].items(): + for parameter, parameter_info in file_info[parameter_type + "_parameters"].items(): if "New Value" not in parameter_info: - logging_error(_("Error in file '%s': '%s' %s parameter '%s'" - " 'New Value' attribute not found."), - self.configuration_steps_filename, filename, parameter_type, parameter) + logging_error( + _("Error in file '%s': '%s' %s parameter '%s' 'New Value' attribute not found."), + self.configuration_steps_filename, + filename, + parameter_type, + parameter, + ) if "Change Reason" not in parameter_info: - logging_error(_("Error in file '%s': '%s' %s parameter '%s'" - " 'Change Reason' attribute not found."), - self.configuration_steps_filename, filename, parameter_type, parameter) + logging_error( + _("Error in file '%s': '%s' %s parameter '%s' 'Change Reason' attribute not found."), + self.configuration_steps_filename, + filename, + parameter_type, + parameter, + ) def compute_parameters(self, filename: str, file_info: dict, parameter_type: str, variables: dict) -> str: """ @@ -106,17 +120,20 @@ def compute_parameters(self, filename: str, file_info: dict, parameter_type: str If the parameter is forced, it is added to the forced_parameters dictionary. If the parameter is derived, it is added to the derived_parameters dictionary. """ - if parameter_type + '_parameters' not in file_info or not variables: + if parameter_type + "_parameters" not in file_info or not variables: return "" - destination = self.forced_parameters if parameter_type == 'forced' else self.derived_parameters - for parameter, parameter_info in file_info[parameter_type + '_parameters'].items(): # pylint: disable=too-many-nested-blocks + destination = self.forced_parameters if parameter_type == "forced" else self.derived_parameters + for parameter, parameter_info in file_info[parameter_type + "_parameters"].items(): # pylint: disable=too-many-nested-blocks try: - if ('fc_parameters' in str(parameter_info["New Value"])) and \ - ('fc_parameters' not in variables or variables['fc_parameters'] == {}): - error_msg = _("In file '{self.configuration_steps_filename}': '{filename}' {parameter_type} " \ - "parameter '{parameter}' could not be computed: 'fc_parameters' not found, is an FC connected?") + if ("fc_parameters" in str(parameter_info["New Value"])) and ( + "fc_parameters" not in variables or variables["fc_parameters"] == {} + ): + error_msg = _( + "In file '{self.configuration_steps_filename}': '{filename}' {parameter_type} " + "parameter '{parameter}' could not be computed: 'fc_parameters' not found, is an FC connected?" + ) error_msg = error_msg.format(**locals()) - if parameter_type == 'forced': + if parameter_type == "forced": logging_error(error_msg) return error_msg logging_warning(error_msg) @@ -125,23 +142,25 @@ def compute_parameters(self, filename: str, file_info: dict, parameter_type: str # convert (combobox) string text to (parameter value) string int or float if isinstance(result, str): - if parameter in variables['doc_dict']: - values = variables['doc_dict'][parameter]['values'] + if parameter in variables["doc_dict"]: + values = variables["doc_dict"][parameter]["values"] if values: result = next(key for key, value in values.items() if value == result) else: - bitmasks = variables['doc_dict'][parameter]['Bitmask'] + bitmasks = variables["doc_dict"][parameter]["Bitmask"] if bitmasks: - result = 2**next(key for key, bitmask in bitmasks.items() if bitmask == result) + result = 2 ** next(key for key, bitmask in bitmasks.items() if bitmask == result) if filename not in destination: destination[filename] = {} destination[filename][parameter] = Par(float(result), parameter_info["Change Reason"]) except (SyntaxError, NameError, KeyError, StopIteration) as _e: - error_msg = _("In file '{self.configuration_steps_filename}': '{filename}' {parameter_type} " \ - "parameter '{parameter}' could not be computed: {_e}") + error_msg = _( + "In file '{self.configuration_steps_filename}': '{filename}' {parameter_type} " + "parameter '{parameter}' could not be computed: {_e}" + ) error_msg = error_msg.format(**locals()) - if parameter_type == 'forced': + if parameter_type == "forced": logging_error(error_msg) return error_msg logging_warning(error_msg) @@ -149,20 +168,21 @@ def compute_parameters(self, filename: str, file_info: dict, parameter_type: str def auto_changed_by(self, selected_file: str): if selected_file in self.configuration_steps: - return self.configuration_steps[selected_file].get('auto_changed_by', '') - return '' + return self.configuration_steps[selected_file].get("auto_changed_by", "") + return "" def jump_possible(self, selected_file: str): if selected_file in self.configuration_steps: - return self.configuration_steps[selected_file].get('jump_possible', {}) + return self.configuration_steps[selected_file].get("jump_possible", {}) return {} def get_documentation_text_and_url(self, selected_file: str, prefix_key: str) -> Tuple[str, str]: - documentation = self.configuration_steps.get(selected_file, {}) if \ - self.configuration_steps else None + documentation = self.configuration_steps.get(selected_file, {}) if self.configuration_steps else None if documentation is None: - text = _("File '{self.configuration_steps_filename}' not found. " \ - "No intermediate parameter configuration steps available") + text = _( + "File '{self.configuration_steps_filename}' not found. " + "No intermediate parameter configuration steps available" + ) text = text.format(**locals()) url = None else: diff --git a/MethodicConfigurator/backend_filesystem_program_settings.py b/MethodicConfigurator/backend_filesystem_program_settings.py index 0f2ef27..0cc149e 100644 --- a/MethodicConfigurator/backend_filesystem_program_settings.py +++ b/MethodicConfigurator/backend_filesystem_program_settings.py @@ -1,33 +1,29 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" -from os import path as os_path -from os import makedirs as os_makedirs -from os import sep as os_sep - -from re import match as re_match -from re import escape as re_escape -from re import sub as re_sub +from json import dump as json_dump +from json import load as json_load # from sys import exit as sys_exit from logging import error as logging_error - -from json import load as json_load -from json import dump as json_dump - +from os import makedirs as os_makedirs +from os import path as os_path +from os import sep as os_sep from platform import system as platform_system +from re import escape as re_escape +from re import match as re_match +from re import sub as re_sub -from platformdirs import site_config_dir -from platformdirs import user_config_dir +from platformdirs import site_config_dir, user_config_dir -from MethodicConfigurator.internationalization import _ +from MethodicConfigurator import _ class ProgramSettings: @@ -38,18 +34,19 @@ class ProgramSettings: templates, and user preferences. It also manages the creation of new vehicle directories and validation of directory names according to specific rules. """ + def __init__(self): pass @staticmethod def application_icon_filepath(): script_dir = os_path.dirname(os_path.abspath(__file__)) - return os_path.join(script_dir, 'ArduPilot_icon.png') + return os_path.join(script_dir, "ArduPilot_icon.png") @staticmethod def application_logo_filepath(): script_dir = os_path.dirname(os_path.abspath(__file__)) - return os_path.join(script_dir, 'ArduPilot_logo.png') + return os_path.join(script_dir, "ArduPilot_logo.png") @staticmethod def create_new_vehicle_dir(new_vehicle_dir: str): @@ -81,7 +78,7 @@ def valid_directory_name(dir_name: str): - bool: True if the directory name matches the allowed pattern, False otherwise. """ # Include os.sep in the pattern - pattern = r'^[\w' + re_escape(os_sep) + '-]+$' + pattern = r"^[\w" + re_escape(os_sep) + "-]+$" return re_match(pattern, dir_name) is not None @staticmethod @@ -99,8 +96,9 @@ def __user_config_dir(): @staticmethod def __site_config_dir(): - site_config_directory = site_config_dir(".ardupilot_methodic_configurator", False, version=None, multipath=False, - ensure_exists=True) + site_config_directory = site_config_dir( + ".ardupilot_methodic_configurator", False, version=None, multipath=False, ensure_exists=True + ) if not os_path.exists(site_config_directory): error_msg = _("The site configuration directory '{site_config_directory}' does not exist.") @@ -118,7 +116,7 @@ def __get_settings_as_dict(): settings = {} try: - with open(settings_path, "r", encoding='utf-8') as settings_file: + with open(settings_path, "r", encoding="utf-8") as settings_file: settings = json_load(settings_file) except FileNotFoundError: # If the file does not exist, it will be created later @@ -143,7 +141,7 @@ def __get_settings_as_dict(): def __set_settings_from_dict(settings): settings_path = os_path.join(ProgramSettings.__user_config_dir(), "settings.json") - with open(settings_path, "w", encoding='utf-8') as settings_file: + with open(settings_path, "w", encoding="utf-8") as settings_file: json_dump(settings, settings_file, indent=4) @staticmethod @@ -154,7 +152,7 @@ def __get_settings_config(): pattern = r"(? SPDX-License-Identifier: GPL-3.0-or-later -''' +""" -from os import path as os_path -from os import walk as os_walk +from json import JSONDecodeError +from json import dump as json_dump +from json import load as json_load # from sys import exit as sys_exit from logging import debug as logging_debug -#from logging import info as logging_info -#from logging import warning as logging_warning -from logging import error as logging_error +# from logging import info as logging_info +# from logging import warning as logging_warning +from logging import error as logging_error +from os import path as os_path +from os import walk as os_walk from re import match as re_match -from json import load as json_load -from json import dump as json_dump -from json import JSONDecodeError - from MethodicConfigurator.backend_filesystem_program_settings import ProgramSettings - +from MethodicConfigurator import _ from MethodicConfigurator.middleware_template_overview import TemplateOverview -from MethodicConfigurator.internationalization import _ - class VehicleComponents: """ This class provides methods to load and save vehicle components configurations from a JSON file. """ + def __init__(self): self.vehicle_components_json_filename = "vehicle_components.json" self.vehicle_components = None @@ -43,7 +41,7 @@ def load_vehicle_components_json_data(self, vehicle_dir: str): data = {} try: filepath = os_path.join(vehicle_dir, self.vehicle_components_json_filename) - with open(filepath, 'r', encoding='utf-8') as file: + with open(filepath, "r", encoding="utf-8") as file: data = json_load(file) except FileNotFoundError: # Normal users do not need this information @@ -56,7 +54,7 @@ def load_vehicle_components_json_data(self, vehicle_dir: str): def save_vehicle_components_json_data(self, data, vehicle_dir: str) -> bool: filepath = os_path.join(vehicle_dir, self.vehicle_components_json_filename) try: - with open(filepath, 'w', encoding='utf-8') as file: + with open(filepath, "w", encoding="utf-8") as file: json_dump(data, file, indent=4) except Exception as e: # pylint: disable=broad-except logging_error(_("Error saving JSON data to file '%s': %s"), filepath, e) @@ -64,12 +62,12 @@ def save_vehicle_components_json_data(self, data, vehicle_dir: str) -> bool: return False def get_fc_fw_type_from_vehicle_components_json(self) -> str: - if self.vehicle_components and 'Components' in self.vehicle_components: - components = self.vehicle_components['Components'] + if self.vehicle_components and "Components" in self.vehicle_components: + components = self.vehicle_components["Components"] else: components = None if components: - fw_type = components.get('Flight Controller', {}).get('Firmware', {}).get('Type', '') + fw_type = components.get("Flight Controller", {}).get("Firmware", {}).get("Type", "") if fw_type in self.supported_vehicles(): return fw_type error_msg = _("Firmware type {fw_type} in {self.vehicle_components_json_filename} is not supported") @@ -77,14 +75,14 @@ def get_fc_fw_type_from_vehicle_components_json(self) -> str: return "" def get_fc_fw_version_from_vehicle_components_json(self) -> str: - if self.vehicle_components and 'Components' in self.vehicle_components: - components = self.vehicle_components['Components'] + if self.vehicle_components and "Components" in self.vehicle_components: + components = self.vehicle_components["Components"] else: components = None if components: - version_str = components.get('Flight Controller', {}).get('Firmware', {}).get('Version', '') - version_str = version_str.lstrip().split(' ')[0] if version_str else '' - if re_match(r'^\d+\.\d+\.\d+$', version_str): + version_str = components.get("Flight Controller", {}).get("Firmware", {}).get("Version", "") + version_str = version_str.lstrip().split(" ")[0] if version_str else "" + if re_match(r"^\d+\.\d+\.\d+$", version_str): return version_str error_msg = _("FW version string {version_str} on {self.vehicle_components_json_filename} is invalid") logging_error(error_msg.format(**locals())) @@ -92,8 +90,7 @@ def get_fc_fw_version_from_vehicle_components_json(self) -> str: @staticmethod def supported_vehicles(): - return ['AP_Periph', 'AntennaTracker', 'ArduCopter', 'ArduPlane', - 'ArduSub', 'Blimp', 'Heli', 'Rover', 'SITL'] + return ["AP_Periph", "AntennaTracker", "ArduCopter", "ArduPlane", "ArduSub", "Blimp", "Heli", "Rover", "SITL"] @staticmethod def get_vehicle_components_overviews(): @@ -114,7 +111,7 @@ def get_vehicle_components_overviews(): vehicle_components = VehicleComponents() comp_data = vehicle_components.load_vehicle_components_json_data(root) if comp_data: - comp_data = comp_data.get('Components', {}) + comp_data = comp_data.get("Components", {}) vehicle_components_overview = TemplateOverview(comp_data) vehicle_components_dict[relative_path] = vehicle_components_overview diff --git a/MethodicConfigurator/backend_flightcontroller.py b/MethodicConfigurator/backend_flightcontroller.py index 123baf3..8fe1767 100644 --- a/MethodicConfigurator/backend_flightcontroller.py +++ b/MethodicConfigurator/backend_flightcontroller.py @@ -1,52 +1,44 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" from logging import debug as logging_debug +from logging import error as logging_error from logging import info as logging_info from logging import warning as logging_warning -from logging import error as logging_error - -from time import sleep as time_sleep -from time import time as time_time -from os import path as os_path from os import name as os_name +from os import path as os_path from os import readlink as os_readlink -from typing import Dict -from typing import List -from typing import Tuple +from time import sleep as time_sleep +from time import time as time_time +from typing import Dict, List, Optional, Tuple import serial.tools.list_ports import serial.tools.list_ports_common - from serial.serialutil import SerialException from MethodicConfigurator.annotate_params import Par - +from MethodicConfigurator.argparse_check_range import CheckRange from MethodicConfigurator.backend_flightcontroller_info import BackendFlightcontrollerInfo from MethodicConfigurator.backend_mavftp import MAVFTP - -from MethodicConfigurator.argparse_check_range import CheckRange - -from MethodicConfigurator.internationalization import _ - +from MethodicConfigurator import _ # adding all this allows pyinstaller to build a working windows executable # note that using --hidden-import does not work for these modules try: from pymavlink import mavutil # import pymavlink.dialects.v20.ardupilotmega -except Exception: # pylint: disable=broad-exception-caught +except Exception: # pylint: disable=broad-exception-caught pass -class FakeSerialForUnitTests(): +class FakeSerialForUnitTests: """ A mock serial class for unit testing purposes. @@ -55,6 +47,7 @@ class FakeSerialForUnitTests(): serial device. It includes methods for reading, writing, and checking the number of bytes in the input buffer, as well as closing the connection. """ + def __init__(self, device: str): self.device = device @@ -80,6 +73,7 @@ class FlightController: master (mavutil.mavlink_connection): The MAVLink connection object. fc_parameters (Dict[str, float]): A dictionary of flight controller parameters. """ + def __init__(self, reboot_time: int): """ Initialize the FlightController communication object. @@ -101,13 +95,12 @@ def discover_connections(self): comports = FlightController.__list_serial_ports() netports = FlightController.__list_network_ports() # list of tuples with the first element being the port name and the second element being the port description - self.__connection_tuples = [(port.device, port.description) for port in comports] + \ - [(port, port) for port in netports] - logging_info(_('Available connection ports are:')) + self.__connection_tuples = [(port.device, port.description) for port in comports] + [(port, port) for port in netports] + logging_info(_("Available connection ports are:")) for port in self.__connection_tuples: logging_info("%s - %s", port[0], port[1]) # now that it is logged, add the 'Add another' tuple - self.__connection_tuples += [tuple([_('Add another'), _('Add another')])] + self.__connection_tuples += [tuple([_("Add another"), _("Add another")])] def disconnect(self): """ @@ -134,7 +127,7 @@ def add_connection(self, connection_string: str): logging_debug(_("Did not add empty connection")) return False - def connect(self, device: str, progress_callback=None, log_errors: bool=True) -> str: + def connect(self, device: str, progress_callback=None, log_errors: bool = True) -> str: """ Establishes a connection to the FlightController using a specified device. @@ -154,15 +147,15 @@ def connect(self, device: str, progress_callback=None, log_errors: bool=True) -> a successful connection. """ if device: - if device == 'none': - return '' + if device == "none": + return "" self.add_connection(device) self.comport = mavutil.SerialPort(device=device, description=device) else: autodetect_serial = self.__auto_detect_serial() if autodetect_serial: # Resolve the soft link if it's a Linux system - if os_name == 'posix': + if os_name == "posix": try: dev = autodetect_serial[0].device logging_debug(_("Auto-detected device %s"), dev) @@ -173,7 +166,7 @@ def connect(self, device: str, progress_callback=None, log_errors: bool=True) -> autodetect_serial[0].device = resolved_path logging_debug(_("Resolved soft link %s to %s"), dev, resolved_path) except OSError: - pass # Not a soft link, proceed with the original device path + pass # Not a soft link, proceed with the original device path self.comport = autodetect_serial[0] # Add the detected serial port to the list of available connections if it is not there if self.comport.device not in [t[0] for t in self.__connection_tuples]: @@ -183,21 +176,28 @@ def connect(self, device: str, progress_callback=None, log_errors: bool=True) -> return self.__create_connection_with_retry(progress_callback=progress_callback, log_errors=log_errors) def __request_banner(self): - '''Request banner information from the flight controller''' + """Request banner information from the flight controller""" # https://mavlink.io/en/messages/ardupilotmega.html#MAV_CMD_DO_SEND_BANNER self.master.mav.command_long_send( self.master.target_system, self.master.target_component, mavutil.mavlink.MAV_CMD_DO_SEND_BANNER, 0, - 0, 0, 0, 0, 0, 0, 0) + 0, + 0, + 0, + 0, + 0, + 0, + 0, + ) def __receive_banner_text(self) -> List[str]: """Starts listening for STATUS_TEXT MAVLink messages.""" start_time = time_time() banner_msgs = [] while True: - msg = self.master.recv_match(type='STATUSTEXT', blocking=False) + msg = self.master.recv_match(type="STATUSTEXT", blocking=False) if msg: if banner_msgs: banner_msgs.append(msg.text) @@ -213,11 +213,19 @@ def __request_message(self, message_id: int): self.info.system_id, self.info.component_id, mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE, - 0, # confirmation - message_id, 0, 0, 0, 0, 0, 0) + 0, # confirmation + message_id, + 0, + 0, + 0, + 0, + 0, + 0, + ) - def __create_connection_with_retry(self, progress_callback, retries: int = 3, - timeout: int = 5, log_errors: bool = True) -> mavutil.mavlink_connection: + def __create_connection_with_retry( + self, progress_callback, retries: int = 3, timeout: int = 5, log_errors: bool = True + ) -> mavutil.mavlink_connection: """ Attempts to create a connection to the flight controller with retries. @@ -236,21 +244,22 @@ def __create_connection_with_retry(self, progress_callback, retries: int = 3, str: An error message if the connection fails after all retries, otherwise an empty string indicating a successful connection. """ - if self.comport is None or self.comport.device == 'test': # FIXME for testing only pylint: disable=fixme + if self.comport is None or self.comport.device == "test": # FIXME for testing only pylint: disable=fixme return "" logging_info(_("Will connect to %s"), self.comport.device) try: # Create the connection - self.master = mavutil.mavlink_connection(device=self.comport.device, timeout=timeout, - retries=retries, progress_callback=progress_callback) + self.master = mavutil.mavlink_connection( + device=self.comport.device, timeout=timeout, retries=retries, progress_callback=progress_callback + ) logging_debug(_("Waiting for MAVLink heartbeat")) m = self.master.wait_heartbeat(timeout=timeout) if m is None: return _("No MAVLink heartbeat received, connection failed.") self.info.set_system_id_and_component_id(m.get_srcSystem(), m.get_srcComponent()) - logging_debug(_("Connection established with systemID %d, componentID %d."), - self.info.system_id, - self.info.component_id) + logging_debug( + _("Connection established with systemID %d, componentID %d."), self.info.system_id, self.info.component_id + ) self.info.set_autopilot(m.autopilot) if self.info.is_supported: @@ -268,7 +277,7 @@ def __create_connection_with_retry(self, progress_callback, retries: int = 3, banner_msgs = self.__receive_banner_text() self.__request_message(mavutil.mavlink.MAVLINK_MSG_ID_AUTOPILOT_VERSION) - m = self.master.recv_match(type='AUTOPILOT_VERSION', blocking=True, timeout=timeout) + m = self.master.recv_match(type="AUTOPILOT_VERSION", blocking=True, timeout=timeout) return self.__process_autopilot_version(m, banner_msgs) except (ConnectionError, SerialException, PermissionError, ConnectionRefusedError) as e: if log_errors: @@ -278,9 +287,11 @@ def __create_connection_with_retry(self, progress_callback, retries: int = 3, def __process_autopilot_version(self, m, banner_msgs) -> str: if m is None: - return _("No AUTOPILOT_VERSION MAVLink message received, connection failed.\n" \ - "Only ArduPilot versions newer than 4.3.8 are supported.\n" \ - "Make sure parameter SERIAL0_PROTOCOL is set to 2") + return _( + "No AUTOPILOT_VERSION MAVLink message received, connection failed.\n" + "Only ArduPilot versions newer than 4.3.8 are supported.\n" + "Make sure parameter SERIAL0_PROTOCOL is set to 2" + ) self.info.set_capabilities(m.capabilities) self.info.set_flight_sw_version(m.flight_sw_version) self.info.set_board_version(m.board_version) @@ -288,22 +299,25 @@ def __process_autopilot_version(self, m, banner_msgs) -> str: self.info.set_os_custom_version(m.os_custom_version) self.info.set_vendor_id_and_product_id(m.vendor_id, m.product_id) - os_custom_version = '' + os_custom_version = "" os_custom_version_index = None for i, msg in enumerate(banner_msgs): - if 'ChibiOS:' in msg: - os_custom_version = msg.split(' ')[1].strip() + if "ChibiOS:" in msg: + os_custom_version = msg.split(" ")[1].strip() if os_custom_version != self.info.os_custom_version: - logging_warning(_("ChibiOS version missmatch: %s (BANNER) != % s (AUTOPILOT_VERSION)"), os_custom_version, - self.info.os_custom_version) + logging_warning( + _("ChibiOS version missmatch: %s (BANNER) != % s (AUTOPILOT_VERSION)"), + os_custom_version, + self.info.os_custom_version, + ) os_custom_version_index = i continue logging_info("FC banner %s", msg) # the banner message after the ChibiOS one contains the FC type - fc_product = '' + fc_product = "" if os_custom_version_index is not None and os_custom_version_index + 1 < len(banner_msgs): - fc_product_banner_substrings = banner_msgs[os_custom_version_index+1].split(' ') + fc_product_banner_substrings = banner_msgs[os_custom_version_index + 1].split(" ") if len(fc_product_banner_substrings) >= 3: fc_product = fc_product_banner_substrings[0] if fc_product != self.info.product: @@ -311,7 +325,7 @@ def __process_autopilot_version(self, m, banner_msgs) -> str: self.info.product = fc_product # force the one from the banner because it is more reliable return "" - def download_params(self, progress_callback=None) -> Tuple[Dict[str, float], Dict[str, 'Par']]: + def download_params(self, progress_callback=None) -> Tuple[Dict[str, float], Dict[str, "Par"]]: """ Requests all flight controller parameters from a MAVLink connection. @@ -320,8 +334,8 @@ def download_params(self, progress_callback=None) -> Tuple[Dict[str, float], Dic Dict[str, Par]: 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' + 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()}, {} @@ -331,8 +345,7 @@ def download_params(self, progress_callback=None) -> Tuple[Dict[str, float], Dic # Check if MAVFTP is supported if self.info.is_mavftp_supported: - logging_info(_("MAVFTP is supported by the %s flight controller"), - self.comport.device) + logging_info(_("MAVFTP is supported by the %s flight controller"), self.comport.device) return self.download_params_via_mavftp(progress_callback) @@ -342,9 +355,7 @@ def download_params(self, progress_callback=None) -> Tuple[Dict[str, float], Dic def __download_params_via_mavlink(self, progress_callback=None) -> Dict[str, float]: logging_debug(_("Will fetch all parameters from the %s flight controller"), self.comport.device) # Request all parameters - self.master.mav.param_request_list_send( - self.master.target_system, self.master.target_component - ) + self.master.mav.param_request_list_send(self.master.target_system, self.master.target_component) # Dictionary to store parameters parameters = {} @@ -352,40 +363,38 @@ def __download_params_via_mavlink(self, progress_callback=None) -> Dict[str, flo # Loop to receive all parameters while True: try: - m = self.master.recv_match(type='PARAM_VALUE', blocking=True, timeout=10) + m = self.master.recv_match(type="PARAM_VALUE", blocking=True, timeout=10) if m is None: break message = m.to_dict() - param_id = message['param_id'] # .decode("utf-8") - param_value = message['param_value'] + param_id = message["param_id"] # .decode("utf-8") + param_value = message["param_value"] parameters[param_id] = param_value - logging_debug(_('Received parameter: %s = %s'), param_id, param_value) + logging_debug(_("Received parameter: %s = %s"), param_id, param_value) # Call the progress callback with the current progress if progress_callback: progress_callback(len(parameters), m.param_count) if m.param_count == len(parameters): - logging_debug(_("Fetched %d parameter values from the %s flight controller"), - m.param_count, self.comport.device) + logging_debug( + _("Fetched %d parameter values from the %s flight controller"), m.param_count, self.comport.device + ) break except Exception as error: # pylint: disable=broad-except - logging_error(_('Error: %s'), error) + logging_error(_("Error: %s"), error) break return parameters - def download_params_via_mavftp(self, progress_callback=None) -> Tuple[Dict[str, float], Dict[str, 'Par']]: - - mavftp = MAVFTP(self.master, - target_system=self.master.target_system, - target_component=self.master.target_component) + def download_params_via_mavftp(self, progress_callback=None) -> Tuple[Dict[str, float], Dict[str, "Par"]]: + mavftp = MAVFTP(self.master, target_system=self.master.target_system, target_component=self.master.target_component) def get_params_progress_callback(completion: float): if progress_callback is not None and completion is not None: - progress_callback(int(completion*100), 100) + progress_callback(int(completion * 100), 100) - complete_param_filename = 'complete.param' - default_param_filename = '00_default.param' + complete_param_filename = "complete.param" + default_param_filename = "00_default.param" mavftp.cmd_getparams([complete_param_filename, default_param_filename], progress_callback=get_params_progress_callback) - ret = mavftp.process_ftp_reply('getparams', timeout=10) + ret = mavftp.process_ftp_reply("getparams", timeout=10) pdict = {} if ret.error_code == 0: # load the parameters from the file @@ -407,19 +416,20 @@ def set_param(self, param_name: str, param_value: float): param_name (str): The name of the parameter to set. param_value (float): The value to set the parameter to. """ - if self.master is None: # FIXME for testing only pylint: disable=fixme + if self.master is None: # FIXME for testing only pylint: disable=fixme return None return self.master.param_set_send(param_name, param_value) - def reset_and_reconnect(self, reset_progress_callback=None, connection_progress_callback=None, - extra_sleep_time: int = None) -> str: + def reset_and_reconnect( + self, reset_progress_callback=None, connection_progress_callback=None, extra_sleep_time: Optional[int] = None + ) -> str: """ Reset the flight controller and reconnect. Args: sleep_time (int, optional): The time in seconds to wait before reconnecting. """ - if self.master is None: # FIXME for testing only pylint: disable=fixme + if self.master is None: # FIXME for testing only pylint: disable=fixme return "" # Issue a reset self.master.reboot_autopilot() @@ -466,29 +476,29 @@ def __list_network_ports(): """ List all available network ports. """ - return ['tcp:127.0.0.1:5760', 'udp:127.0.0.1:14550'] + return ["tcp:127.0.0.1:5760", "udp:127.0.0.1:14550"] -# pylint: disable=duplicate-code + # pylint: disable=duplicate-code def __auto_detect_serial(self): serial_list = [] preferred_ports = [ - '*FTDI*', + "*FTDI*", "*Arduino_Mega_2560*", "*3D*", "*USB_to_UART*", - '*Ardu*', - '*PX4*', - '*Hex_*', - '*Holybro_*', - '*mRo*', - '*FMU*', - '*Swift-Flyer*', - '*Serial*', - '*CubePilot*', - '*Qiotek*', + "*Ardu*", + "*PX4*", + "*Hex_*", + "*Holybro_*", + "*mRo*", + "*FMU*", + "*Swift-Flyer*", + "*Serial*", + "*CubePilot*", + "*Qiotek*", ] for connection in self.__connection_tuples: - if connection[1] and 'mavlink' in connection[1].lower(): + if connection[1] and "mavlink" in connection[1].lower(): serial_list.append(mavutil.SerialPort(device=connection[0], description=connection[1])) if len(serial_list) == 1: # selected automatically if unique @@ -503,7 +513,8 @@ def __auto_detect_serial(self): serial_list.pop(1) return serial_list -# pylint: enable=duplicate-code + + # pylint: enable=duplicate-code def get_connection_tuples(self): """ @@ -512,38 +523,41 @@ def get_connection_tuples(self): return self.__connection_tuples def upload_file(self, local_filename: str, remote_filename: str, progress_callback=None): - """ Upload a file to the flight controller. """ + """Upload a file to the flight controller.""" if self.master is None: return False - mavftp = MAVFTP(self.master, - target_system=self.master.target_system, - target_component=self.master.target_component) + mavftp = MAVFTP(self.master, target_system=self.master.target_system, target_component=self.master.target_component) def put_progress_callback(completion: float): if progress_callback is not None and completion is not None: - progress_callback(int(completion*100), 100) + progress_callback(int(completion * 100), 100) mavftp.cmd_put([local_filename, remote_filename], progress_callback=put_progress_callback) - ret = mavftp.process_ftp_reply('CreateFile', timeout=10) + ret = mavftp.process_ftp_reply("CreateFile", timeout=10) if ret.error_code != 0: ret.display_message() return ret.error_code == 0 @staticmethod def add_argparse_arguments(parser): - parser.add_argument('--device', - type=str, - default="", - help=_('MAVLink connection string to the flight controller. ' - 'If set to "none" no connection is made.' - ' Defaults to autodetection') - ) - parser.add_argument('-r', '--reboot-time', - type=int, - min=5, - max=50, - action=CheckRange, - default=7, - help=_('Flight controller reboot time. ' - 'Default is %(default)s')) + parser.add_argument( + "--device", + type=str, + default="", + help=_( + "MAVLink connection string to the flight controller. " + 'If set to "none" no connection is made.' + " Defaults to autodetection" + ), + ) + parser.add_argument( + "-r", + "--reboot-time", + type=int, + min=5, + max=50, + action=CheckRange, + default=7, + help=_("Flight controller reboot time. Default is %(default)s"), + ) return parser diff --git a/MethodicConfigurator/backend_flightcontroller_info.py b/MethodicConfigurator/backend_flightcontroller_info.py index d1646a5..a62b0b4 100644 --- a/MethodicConfigurator/backend_flightcontroller_info.py +++ b/MethodicConfigurator/backend_flightcontroller_info.py @@ -1,21 +1,22 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" # adding all this allows pyinstaller to build a working windows executable # note that using --hidden-import does not work for these modules try: from pymavlink import mavutil # import pymavlink.dialects.v20.ardupilotmega -except Exception: # pylint: disable=broad-exception-caught +except Exception: # pylint: disable=broad-exception-caught pass + class BackendFlightcontrollerInfo: # pylint: disable=too-many-instance-attributes """ Handle flight controller information. @@ -23,6 +24,7 @@ class BackendFlightcontrollerInfo: # pylint: disable=too-many-instance-attribut It includes methods for setting various attributes such as system ID, component ID, autopilot type, vehicle type, and capabilities among others. """ + def __init__(self): self.system_id = None self.component_id = None @@ -58,7 +60,7 @@ def get_info(self): "OS Git Hash": self.os_custom_version, "Capabilities": self.capabilities, "System ID": self.system_id, - "Component ID": self.component_id + "Component ID": self.component_id, } def set_system_id_and_component_id(self, system_id, component_id): @@ -82,10 +84,10 @@ def set_board_version(self, board_version): self.board_version = board_version def set_flight_custom_version(self, flight_custom_version): - self.flight_custom_version = ''.join(chr(c) for c in flight_custom_version) + self.flight_custom_version = "".join(chr(c) for c in flight_custom_version) def set_os_custom_version(self, os_custom_version): - self.os_custom_version = ''.join(chr(c) for c in os_custom_version) + self.os_custom_version = "".join(chr(c) for c in os_custom_version) def set_vendor_id_and_product_id(self, vendor_id, product_id): pid_vid_dict = self.__list_ardupilot_supported_usb_pid_vid() @@ -98,7 +100,7 @@ def set_vendor_id_and_product_id(self, vendor_id, product_id): self.vendor_and_vendor_id = f"{self.vendor} ({self.vendor_id})" self.product_id = f"0x{product_id:04X}" if product_id else "Unknown" - if vendor_id and product_id and product_id in pid_vid_dict[vendor_id]['PID']: + if vendor_id and product_id and product_id in pid_vid_dict[vendor_id]["PID"]: self.product = f"{pid_vid_dict[vendor_id]['PID'][product_id]}" elif product_id: self.product = "Unknown" @@ -110,12 +112,12 @@ def set_capabilities(self, capabilities): @staticmethod def __decode_flight_sw_version(flight_sw_version): - '''decode 32 bit flight_sw_version mavlink parameter - corresponds to ArduPilot encoding in GCS_MAVLINK::send_autopilot_version''' - fw_type_id = (flight_sw_version >> 0) % 256 # noqa E221, E222 - patch = (flight_sw_version >> 8) % 256 # noqa E221, E222 - minor = (flight_sw_version >> 16) % 256 # noqa E221 - major = (flight_sw_version >> 24) % 256 # noqa E221 + """decode 32 bit flight_sw_version mavlink parameter + corresponds to ArduPilot encoding in GCS_MAVLINK::send_autopilot_version""" + fw_type_id = (flight_sw_version >> 0) % 256 # E221, E222 + patch = (flight_sw_version >> 8) % 256 # E221, E222 + minor = (flight_sw_version >> 16) % 256 # E221 + major = (flight_sw_version >> 24) % 256 # E221 if fw_type_id == 0: fw_type = "dev" elif fw_type_id == 64: @@ -130,12 +132,11 @@ def __decode_flight_sw_version(flight_sw_version): fw_type = "undefined" return major, minor, patch, fw_type - @staticmethod def __decode_flight_capabilities(capabilities): - '''Decode 32 bit flight controller capabilities bitmask mavlink parameter. + """Decode 32 bit flight controller capabilities bitmask mavlink parameter. Returns a dict of concise English descriptions of each active capability. - ''' + """ capabilities_dict = {} # Iterate through each bit in the capabilities bitmask @@ -145,29 +146,28 @@ def __decode_flight_capabilities(capabilities): # Use the bit value to get the corresponding capability enum capability = mavutil.mavlink.enums["MAV_PROTOCOL_CAPABILITY"].get(1 << bit, "Unknown capability") - if hasattr(capability, 'description'): + if hasattr(capability, "description"): # Append the abbreviated name and description of the capability dictionary capabilities_dict[capability.name.replace("MAV_PROTOCOL_CAPABILITY_", "")] = capability.description else: - capabilities_dict[f'BIT{bit}'] = capability + capabilities_dict[f"BIT{bit}"] = capability return capabilities_dict - # see for more info: # import pymavlink.dialects.v20.ardupilotmega # pymavlink.dialects.v20.ardupilotmega.enums["MAV_TYPE"] @staticmethod def __decode_mav_type(mav_type): - return mavutil.mavlink.enums["MAV_TYPE"].get(mav_type, - mavutil.mavlink.EnumEntry("None", "Unknown type")).description - + return mavutil.mavlink.enums["MAV_TYPE"].get(mav_type, mavutil.mavlink.EnumEntry("None", "Unknown type")).description @staticmethod def __decode_mav_autopilot(mav_autopilot): - return mavutil.mavlink.enums["MAV_AUTOPILOT"].get(mav_autopilot, - mavutil.mavlink.EnumEntry("None", "Unknown type")).description - + return ( + mavutil.mavlink.enums["MAV_AUTOPILOT"] + .get(mav_autopilot, mavutil.mavlink.EnumEntry("None", "Unknown type")) + .description + ) @staticmethod def __classify_vehicle_type(mav_type_int): @@ -182,48 +182,48 @@ def __classify_vehicle_type(mav_type_int): """ # Define the mapping from MAV_TYPE_* integer to vehicle type category mav_type_to_vehicle_type = { - mavutil.mavlink.MAV_TYPE_FIXED_WING: 'ArduPlane', - mavutil.mavlink.MAV_TYPE_QUADROTOR: 'ArduCopter', - mavutil.mavlink.MAV_TYPE_COAXIAL: 'Heli', - mavutil.mavlink.MAV_TYPE_HELICOPTER: 'Heli', - mavutil.mavlink.MAV_TYPE_ANTENNA_TRACKER: 'AntennaTracker', - mavutil.mavlink.MAV_TYPE_GCS: 'AP_Periph', - mavutil.mavlink.MAV_TYPE_AIRSHIP: 'ArduBlimp', - mavutil.mavlink.MAV_TYPE_FREE_BALLOON: 'ArduBlimp', - mavutil.mavlink.MAV_TYPE_ROCKET: 'ArduCopter', - mavutil.mavlink.MAV_TYPE_GROUND_ROVER: 'Rover', - mavutil.mavlink.MAV_TYPE_SURFACE_BOAT: 'Rover', - mavutil.mavlink.MAV_TYPE_SUBMARINE: 'ArduSub', - mavutil.mavlink.MAV_TYPE_HEXAROTOR: 'ArduCopter', - mavutil.mavlink.MAV_TYPE_OCTOROTOR: 'ArduCopter', - mavutil.mavlink.MAV_TYPE_TRICOPTER: 'ArduCopter', - mavutil.mavlink.MAV_TYPE_FLAPPING_WING: 'ArduPlane', - mavutil.mavlink.MAV_TYPE_KITE: 'ArduPlane', - mavutil.mavlink.MAV_TYPE_ONBOARD_CONTROLLER: 'AP_Periph', - mavutil.mavlink.MAV_TYPE_VTOL_DUOROTOR: 'ArduPlane', - mavutil.mavlink.MAV_TYPE_VTOL_QUADROTOR: 'ArduPlane', - mavutil.mavlink.MAV_TYPE_VTOL_TILTROTOR: 'ArduPlane', - mavutil.mavlink.MAV_TYPE_VTOL_RESERVED2: 'ArduPlane', - mavutil.mavlink.MAV_TYPE_VTOL_RESERVED3: 'ArduPlane', - mavutil.mavlink.MAV_TYPE_VTOL_RESERVED4: 'ArduPlane', - mavutil.mavlink.MAV_TYPE_VTOL_RESERVED5: 'ArduPlane', - mavutil.mavlink.MAV_TYPE_GIMBAL: 'AP_Periph', - mavutil.mavlink.MAV_TYPE_ADSB: 'AP_Periph', - mavutil.mavlink.MAV_TYPE_PARAFOIL: 'ArduPlane', - mavutil.mavlink.MAV_TYPE_DODECAROTOR: 'ArduCopter', - mavutil.mavlink.MAV_TYPE_CAMERA: 'AP_Periph', - mavutil.mavlink.MAV_TYPE_CHARGING_STATION: 'AP_Periph', - mavutil.mavlink.MAV_TYPE_FLARM: 'AP_Periph', - mavutil.mavlink.MAV_TYPE_SERVO: 'AP_Periph', - mavutil.mavlink.MAV_TYPE_ODID: 'AP_Periph', - mavutil.mavlink.MAV_TYPE_DECAROTOR: 'ArduCopter', - mavutil.mavlink.MAV_TYPE_BATTERY: 'AP_Periph', - mavutil.mavlink.MAV_TYPE_PARACHUTE: 'AP_Periph', - mavutil.mavlink.MAV_TYPE_LOG: 'AP_Periph', - mavutil.mavlink.MAV_TYPE_OSD: 'AP_Periph', - mavutil.mavlink.MAV_TYPE_IMU: 'AP_Periph', - mavutil.mavlink.MAV_TYPE_GPS: 'AP_Periph', - mavutil.mavlink.MAV_TYPE_WINCH: 'AP_Periph', + mavutil.mavlink.MAV_TYPE_FIXED_WING: "ArduPlane", + mavutil.mavlink.MAV_TYPE_QUADROTOR: "ArduCopter", + mavutil.mavlink.MAV_TYPE_COAXIAL: "Heli", + mavutil.mavlink.MAV_TYPE_HELICOPTER: "Heli", + mavutil.mavlink.MAV_TYPE_ANTENNA_TRACKER: "AntennaTracker", + mavutil.mavlink.MAV_TYPE_GCS: "AP_Periph", + mavutil.mavlink.MAV_TYPE_AIRSHIP: "ArduBlimp", + mavutil.mavlink.MAV_TYPE_FREE_BALLOON: "ArduBlimp", + mavutil.mavlink.MAV_TYPE_ROCKET: "ArduCopter", + mavutil.mavlink.MAV_TYPE_GROUND_ROVER: "Rover", + mavutil.mavlink.MAV_TYPE_SURFACE_BOAT: "Rover", + mavutil.mavlink.MAV_TYPE_SUBMARINE: "ArduSub", + mavutil.mavlink.MAV_TYPE_HEXAROTOR: "ArduCopter", + mavutil.mavlink.MAV_TYPE_OCTOROTOR: "ArduCopter", + mavutil.mavlink.MAV_TYPE_TRICOPTER: "ArduCopter", + mavutil.mavlink.MAV_TYPE_FLAPPING_WING: "ArduPlane", + mavutil.mavlink.MAV_TYPE_KITE: "ArduPlane", + mavutil.mavlink.MAV_TYPE_ONBOARD_CONTROLLER: "AP_Periph", + mavutil.mavlink.MAV_TYPE_VTOL_DUOROTOR: "ArduPlane", + mavutil.mavlink.MAV_TYPE_VTOL_QUADROTOR: "ArduPlane", + mavutil.mavlink.MAV_TYPE_VTOL_TILTROTOR: "ArduPlane", + mavutil.mavlink.MAV_TYPE_VTOL_RESERVED2: "ArduPlane", + mavutil.mavlink.MAV_TYPE_VTOL_RESERVED3: "ArduPlane", + mavutil.mavlink.MAV_TYPE_VTOL_RESERVED4: "ArduPlane", + mavutil.mavlink.MAV_TYPE_VTOL_RESERVED5: "ArduPlane", + mavutil.mavlink.MAV_TYPE_GIMBAL: "AP_Periph", + mavutil.mavlink.MAV_TYPE_ADSB: "AP_Periph", + mavutil.mavlink.MAV_TYPE_PARAFOIL: "ArduPlane", + mavutil.mavlink.MAV_TYPE_DODECAROTOR: "ArduCopter", + mavutil.mavlink.MAV_TYPE_CAMERA: "AP_Periph", + mavutil.mavlink.MAV_TYPE_CHARGING_STATION: "AP_Periph", + mavutil.mavlink.MAV_TYPE_FLARM: "AP_Periph", + mavutil.mavlink.MAV_TYPE_SERVO: "AP_Periph", + mavutil.mavlink.MAV_TYPE_ODID: "AP_Periph", + mavutil.mavlink.MAV_TYPE_DECAROTOR: "ArduCopter", + mavutil.mavlink.MAV_TYPE_BATTERY: "AP_Periph", + mavutil.mavlink.MAV_TYPE_PARACHUTE: "AP_Periph", + mavutil.mavlink.MAV_TYPE_LOG: "AP_Periph", + mavutil.mavlink.MAV_TYPE_OSD: "AP_Periph", + mavutil.mavlink.MAV_TYPE_IMU: "AP_Periph", + mavutil.mavlink.MAV_TYPE_GPS: "AP_Periph", + mavutil.mavlink.MAV_TYPE_WINCH: "AP_Periph", # Add more mappings as needed } @@ -238,31 +238,40 @@ def __list_ardupilot_supported_usb_pid_vid(): source: https://ardupilot.org/dev/docs/USB-IDs.html """ return { - 0x0483: {'vendor': 'ST Microelectronics', 'PID': {0x5740: 'ChibiOS'}}, - 0x1209: {'vendor': 'ArduPilot', 'PID': {0x5740: 'MAVLink', - 0x5741: 'Bootloader', - } - }, - 0x16D0: {'vendor': 'ArduPilot', 'PID': {0x0E65: 'MAVLink'}}, - 0x26AC: {'vendor': '3D Robotics', 'PID': {}}, - 0x2DAE: {'vendor': 'CubePilot', 'PID': {0x1001: 'CubeBlack bootloader', - 0x1011: 'CubeBlack', - 0x1101: 'CubeBlack+', - 0x1002: 'CubeYellow bootloader', - 0x1012: 'CubeYellow', - 0x1005: 'CubePurple bootloader', - 0x1015: 'CubePurple', - 0x1016: 'CubeOrange', - 0x1058: 'CubeOrange+', - 0x1059: 'CubeRed' - } - }, - 0x3162: {'vendor': 'Holybro', 'PID': {0x004B: 'Durandal'}}, - 0x27AC: {'vendor': 'Laser Navigation', 'PID': {0x1151: 'VRBrain-v51', - 0x1152: 'VRBrain-v52', - 0x1154: 'VRBrain-v54', - 0x1910: 'VRCore-v10', - 0x1351: 'VRUBrain-v51', - } - }, + 0x0483: {"vendor": "ST Microelectronics", "PID": {0x5740: "ChibiOS"}}, + 0x1209: { + "vendor": "ArduPilot", + "PID": { + 0x5740: "MAVLink", + 0x5741: "Bootloader", + }, + }, + 0x16D0: {"vendor": "ArduPilot", "PID": {0x0E65: "MAVLink"}}, + 0x26AC: {"vendor": "3D Robotics", "PID": {}}, + 0x2DAE: { + "vendor": "CubePilot", + "PID": { + 0x1001: "CubeBlack bootloader", + 0x1011: "CubeBlack", + 0x1101: "CubeBlack+", + 0x1002: "CubeYellow bootloader", + 0x1012: "CubeYellow", + 0x1005: "CubePurple bootloader", + 0x1015: "CubePurple", + 0x1016: "CubeOrange", + 0x1058: "CubeOrange+", + 0x1059: "CubeRed", + }, + }, + 0x3162: {"vendor": "Holybro", "PID": {0x004B: "Durandal"}}, + 0x27AC: { + "vendor": "Laser Navigation", + "PID": { + 0x1151: "VRBrain-v51", + 0x1152: "VRBrain-v52", + 0x1154: "VRBrain-v54", + 0x1910: "VRCore-v10", + 0x1351: "VRUBrain-v51", + }, + }, } diff --git a/MethodicConfigurator/backend_mavftp.py b/MethodicConfigurator/backend_mavftp.py index 0475c1c..46e4ea0 100644 --- a/MethodicConfigurator/backend_mavftp.py +++ b/MethodicConfigurator/backend_mavftp.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 -''' +""" MAVLink File Transfer Protocol support - https://mavlink.io/en/services/ftp.html Original from MAVProxy/MAVProxy/modules/mavproxy_ftp.py @@ -9,29 +9,21 @@ SPDX-FileCopyrightText: 2011-2024 Andrew Tridgell, 2024 Amilcar Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' - -from argparse import ArgumentParser +""" import logging - -import struct -import time -import random import os - -from io import BytesIO as SIO - +import random +import struct import sys - -from typing import Dict -from typing import Tuple - +import time +from argparse import ArgumentParser from datetime import datetime +from io import BytesIO as SIO +from typing import Dict, Tuple from pymavlink import mavutil - # pylint: disable=too-many-lines # pylint: disable=invalid-name # opcodes @@ -82,6 +74,7 @@ MAX_Payload = 239 # pylint: enable=invalid-name + class FTP_OP: # pylint: disable=invalid-name, too-many-instance-attributes """ Represents an operation in the MAVLink File Transfer Protocol (FTP). @@ -89,21 +82,32 @@ class FTP_OP: # pylint: disable=invalid-name, too-many-instance-attributes This class encapsulates the details of a single FTP operation such as reading, writing, listing directories, etc., including the necessary parameters and payload for the operation. """ - def __init__(self, seq, session, opcode, size, # pylint: disable=too-many-arguments - req_opcode, burst_complete, offset, payload): - self.seq = seq # Sequence number for the operation. - self.session = session # Session identifier. - self.opcode = opcode # Operation code indicating the type of FTP operation. - self.size = size # Size of the operation. - self.req_opcode = req_opcode # Request operation code. + + def __init__( # pylint: disable=too-many-arguments + self, + seq, + session, + opcode, + size, + req_opcode, + burst_complete, + offset, + payload, + ): + self.seq = seq # Sequence number for the operation. + self.session = session # Session identifier. + self.opcode = opcode # Operation code indicating the type of FTP operation. + self.size = size # Size of the operation. + self.req_opcode = req_opcode # Request operation code. self.burst_complete = burst_complete # (bool) Flag indicating if the burst transfer is complete. - self.offset = offset # Offset for read/write operations. - self.payload = payload # (bytes) Payload for the operation. + self.offset = offset # Offset for read/write operations. + self.payload = payload # (bytes) Payload for the operation. def pack(self): - '''pack message''' - ret = struct.pack(" 0: ret += f" [{self.payload[0]}]" return ret @@ -137,9 +143,10 @@ class WriteQueue: # pylint: disable=too-few-public-methods Keeps track of offsets and sizes for pending write operations to ensure orderly processing. """ + def __init__(self, ofs: int, size: int): - self.ofs = ofs # Offset where the write operation starts. - self.size = size # Size of the data to be written. + self.ofs = ofs # Offset where the write operation starts. + self.size = size # Size of the data to be written. self.last_send = 0 # Timestamp of the last send operation. @@ -147,9 +154,10 @@ class ParamData: """ A class to manage parameter values and defaults for ArduPilot configuration. """ + def __init__(self): - self.params = [] # params as (name, value, ptype) - self.defaults = None # defaults as (name, value, ptype) + self.params = [] # params as (name, value, ptype) + self.defaults = None # defaults as (name, value, ptype) def add_param(self, name, value, ptype): self.params.append((name, value, ptype)) @@ -162,6 +170,7 @@ def add_default(self, name, value, ptype): class MAVFTPSetting: # pylint: disable=too-few-public-methods """A single MAVFTP setting with a name, type, value and default value.""" + def __init__(self, name, s_type, default): self.name = name self.type = s_type @@ -171,6 +180,7 @@ def __init__(self, name, s_type, default): class MAVFTPSettings: """A collection of MAVFTP settings.""" + def __init__(self, s_vars): self._vars = {} for v in s_vars: @@ -191,7 +201,7 @@ def __getattr__(self, name): raise AttributeError from exc def __setattr__(self, name, value): - if name[0] == '_': + if name[0] == "_": self.__dict__[name] = value return if name in self._vars: @@ -202,8 +212,16 @@ def __setattr__(self, name, value): class MAVFTPReturn: """The result of a MAVFTP operation.""" - def __init__(self, operation_name: str, error_code: int, system_error: int=0, # pylint: disable=too-many-arguments - invalid_error_code: int=0, invalid_opcode: int=0, invalid_payload_size: int=0): + + def __init__( # pylint: disable=too-many-arguments + self, + operation_name: str, + error_code: int, + system_error: int = 0, + invalid_error_code: int = 0, + invalid_opcode: int = 0, + invalid_payload_size: int = 0, + ): self.operation_name = operation_name self.error_code = error_code self.system_error = system_error @@ -269,18 +287,27 @@ class MAVFTP: # pylint: disable=too-many-instance-attributes Handles file operations such as reading, writing, listing directories, and managing sessions. """ - def __init__(self, master, target_system, target_component, - settings=MAVFTPSettings( - [('debug', int, 0), - ('pkt_loss_tx', int, 0), - ('pkt_loss_rx', int, 0), - ('max_backlog', int, 5), - ('burst_read_size', int, 80), - ('write_size', int, 80), - ('write_qsize', int, 5), - ('idle_detection_time', float, 3.7), - ('read_retry_time', float, 1.0), - ('retry_time', float, 0.5)])): + + def __init__( + self, + master, + target_system, + target_component, + settings=MAVFTPSettings( + [ + ("debug", int, 0), + ("pkt_loss_tx", int, 0), + ("pkt_loss_rx", int, 0), + ("max_backlog", int, 5), + ("burst_read_size", int, 80), + ("write_size", int, 80), + ("write_qsize", int, 5), + ("idle_detection_time", float, 3.7), + ("read_retry_time", float, 1.0), + ("retry_time", float, 0.5), + ] + ), + ): self.ftp_settings = settings self.seq = 0 self.session = 0 @@ -327,48 +354,48 @@ def __init__(self, master, target_system, target_component, # Reset the flight controller FTP state-machine self.__send(FTP_OP(self.seq, self.session, OP_ResetSessions, 0, 0, 0, 0, None)) - self.process_ftp_reply('ResetSessions') + self.process_ftp_reply("ResetSessions") def cmd_ftp(self, args) -> MAVFTPReturn: # pylint: disable=too-many-return-statements, too-many-branches - '''FTP operations''' + """FTP operations""" usage = "Usage: ftp " if len(args) < 1: logging.error(usage) return MAVFTPReturn("FTP command", ERR_InvalidArguments) - if args[0] == 'list': + if args[0] == "list": return self.cmd_list(args[1:]) if args[0] == "set": return self.ftp_settings.command(args[1:]) - if args[0] == 'get': + if args[0] == "get": return self.cmd_get(args[1:]) - if args[0] == 'getparams': + if args[0] == "getparams": return self.cmd_getparams(args[1:]) - if args[0] == 'put': + if args[0] == "put": return self.cmd_put(args[1:]) - if args[0] == 'rm': + if args[0] == "rm": return self.cmd_rm(args[1:]) - if args[0] == 'rmdir': + if args[0] == "rmdir": return self.cmd_rmdir(args[1:]) - if args[0] == 'rename': + if args[0] == "rename": return self.cmd_rename(args[1:]) - if args[0] == 'mkdir': + if args[0] == "mkdir": return self.cmd_mkdir(args[1:]) - if args[0] == 'crc': + if args[0] == "crc": return self.cmd_crc(args[1:]) - if args[0] == 'status': + if args[0] == "status": return self.cmd_status() - if args[0] == 'cancel': + if args[0] == "cancel": return self.cmd_cancel() logging.error(usage) return MAVFTPReturn("FTP command", ERR_InvalidArguments) def __send(self, op): - '''send a request''' + """send a request""" op.seq = self.seq payload = op.pack() plen = len(payload) if plen < MAX_Payload + HDR_Len: - payload.extend(bytearray([0]*((HDR_Len+MAX_Payload)-plen))) + payload.extend(bytearray([0] * ((HDR_Len + MAX_Payload) - plen))) self.master.mav.file_transfer_protocol_send(self.network, self.target_system, self.target_component, payload) self.seq = (self.seq + 1) % 256 self.last_op = op @@ -379,7 +406,7 @@ def __send(self, op): self.last_send_time = now def __terminate_session(self): - '''terminate current session''' + """terminate current session""" self.__send(FTP_OP(self.seq, self.session, OP_TerminateSession, 0, 0, 0, 0, None)) self.fh = None self.filename = None @@ -408,43 +435,43 @@ def __terminate_session(self): self.duplicates = 0 if self.ftp_settings.debug > 0: logging.info("FTP: Terminated session") - self.process_ftp_reply('TerminateSession') + self.process_ftp_reply("TerminateSession") self.session = (self.session + 1) % 256 def cmd_list(self, args) -> MAVFTPReturn: - '''list files''' + """list files""" if len(args) == 0: - dname = '/' + dname = "/" elif len(args) == 1: dname = args[0] else: logging.error("Usage: list [directory]") return MAVFTPReturn("ListDirectory", ERR_InvalidArguments) logging.info("Listing %s", dname) - enc_dname = bytearray(dname, 'ascii') + enc_dname = bytearray(dname, "ascii") self.total_size = 0 self.dir_offset = 0 op = FTP_OP(self.seq, self.session, OP_ListDirectory, len(enc_dname), 0, 0, self.dir_offset, enc_dname) self.__send(op) - return self.process_ftp_reply('ListDirectory') + return self.process_ftp_reply("ListDirectory") def __handle_list_reply(self, op, _m) -> MAVFTPReturn: - '''handle OP_ListDirectory reply''' + """handle OP_ListDirectory reply""" if op.opcode == OP_Ack: - dentries = sorted(op.payload.split(b'\x00')) - #logging.info(dentries) + dentries = sorted(op.payload.split(b"\x00")) + # logging.info(dentries) for d in dentries: if len(d) == 0: continue self.dir_offset += 1 try: - d = str(d, 'ascii') + d = str(d, "ascii") except Exception: # pylint: disable=broad-exception-caught continue - if d[0] == 'D': + if d[0] == "D": logging.info(" D %s", d[1:]) - elif d[0] == 'F': - (name, size) = d[1:].split('\t') + elif d[0] == "F": + (name, size) = d[1:].split("\t") size = int(size) self.total_size += size logging.info(" %s\t%u", name, size) @@ -462,7 +489,7 @@ def __handle_list_reply(self, op, _m) -> MAVFTPReturn: return MAVFTPReturn("ListDirectory", ERR_None) def cmd_get(self, args, callback=None, progress_callback=None) -> MAVFTPReturn: - '''get file''' + """get file""" if len(args) == 0 or len(args) > 2: logging.error("Usage: get [FILENAME ]") return MAVFTPReturn("OpenFileRO", ERR_InvalidArguments) @@ -485,29 +512,28 @@ def cmd_get(self, args, callback=None, progress_callback=None) -> MAVFTPReturn: elif self.burst_size > 239: self.burst_size = 239 self.remote_file_size = None - enc_fname = bytearray(fname, 'ascii') + enc_fname = bytearray(fname, "ascii") self.open_retries = 0 op = FTP_OP(self.seq, self.session, OP_OpenFileRO, len(enc_fname), 0, 0, 0, enc_fname) self.__send(op) return MAVFTPReturn("OpenFileRO", ERR_None) def __handle_open_ro_reply(self, op, _m) -> MAVFTPReturn: - '''handle OP_OpenFileRO reply''' + """handle OP_OpenFileRO reply""" if op.opcode == OP_Ack: if self.filename is None: - return MAVFTPReturn('OpenFileRO', ERR_FileNotFound) + return MAVFTPReturn("OpenFileRO", ERR_FileNotFound) try: - if self.callback is not None or self.filename == '-': + if self.callback is not None or self.filename == "-": self.fh = SIO() else: - self.fh = open(self.filename, 'wb') # pylint: disable=consider-using-with + self.fh = open(self.filename, "wb") # pylint: disable=consider-using-with except Exception as ex: # pylint: disable=broad-except logging.error("FTP: Failed to open local file %s: %s", self.filename, ex) self.__terminate_session() - return MAVFTPReturn('OpenFileRO', ERR_FileNotFound) + return MAVFTPReturn("OpenFileRO", ERR_FileNotFound) if op.size == 4 and len(op.payload) >= 4: - self.remote_file_size = op.payload[0] + (op.payload[1] << 8) + (op.payload[2] << 16) + \ - (op.payload[3] << 24) + self.remote_file_size = op.payload[0] + (op.payload[1] << 8) + (op.payload[2] << 16) + (op.payload[3] << 24) if self.ftp_settings.debug > 0: logging.info("Remote file size: %u", self.remote_file_size) else: @@ -515,7 +541,7 @@ def __handle_open_ro_reply(self, op, _m) -> MAVFTPReturn: read = FTP_OP(self.seq, self.session, OP_BurstReadFile, self.burst_size, 0, 0, 0, None) self.last_burst_read = time.time() self.__send(read) - return MAVFTPReturn('OpenFileRO', ERR_None) + return MAVFTPReturn("OpenFileRO", ERR_None) ret = self.__decode_ftp_ack_and_nack(op) if self.callback is None or self.ftp_settings.debug > 0: @@ -524,8 +550,8 @@ def __handle_open_ro_reply(self, op, _m) -> MAVFTPReturn: return ret def __check_read_finished(self): - '''check if download has completed''' - #logging.debug("FTP: check_read_finished: %s %s", self.reached_eof, self.read_gaps) + """check if download has completed""" + # logging.debug("FTP: check_read_finished: %s %s", self.reached_eof, self.read_gaps) if self.reached_eof and len(self.read_gaps) == 0: ofs = self.fh.tell() dt = time.time() - self.op_start @@ -536,7 +562,7 @@ def __check_read_finished(self): self.callback = None elif self.filename == "-": self.fh.seek(0) - print(self.fh.read().decode('utf-8')) + print(self.fh.read().decode("utf-8")) else: logging.info("Got %u bytes from %s in %.2fs %.1fkByte/s", ofs, self.filename, dt, rate) self.remote_file_size = None @@ -545,27 +571,27 @@ def __check_read_finished(self): return False def __write_payload(self, op): - '''write payload from a read op''' + """write payload from a read op""" self.fh.seek(op.offset) self.fh.write(op.payload) self.read_total += len(op.payload) if self.callback_progress is not None and self.remote_file_size: - self.callback_progress(self.read_total/self.remote_file_size) + self.callback_progress(self.read_total / self.remote_file_size) def __handle_burst_read(self, op, _m) -> MAVFTPReturn: # pylint: disable=too-many-branches, too-many-statements, too-many-return-statements - '''handle OP_BurstReadFile reply''' + """handle OP_BurstReadFile reply""" if self.ftp_settings.pkt_loss_tx > 0: if random.uniform(0, 100) < self.ftp_settings.pkt_loss_tx: if self.ftp_settings.debug > 0: logging.warning("FTP: dropping TX") - return MAVFTPReturn('BurstReadFile', ERR_Fail) + return MAVFTPReturn("BurstReadFile", ERR_Fail) if self.fh is None or self.filename is None: if op.session != self.session: # old session - return MAVFTPReturn('BurstReadFile', ERR_InvalidSession) + return MAVFTPReturn("BurstReadFile", ERR_InvalidSession) logging.warning("FTP: Unexpected burst read reply. Will be discarded") logging.info(op) - return MAVFTPReturn('BurstReadFile', ERR_Fail) + return MAVFTPReturn("BurstReadFile", ERR_Fail) self.last_burst_read = time.time() size = len(op.payload) if size > self.burst_size: @@ -587,14 +613,14 @@ def __handle_burst_read(self, op, _m) -> MAVFTPReturn: # pylint: disable=too-ma if self.ftp_settings.debug > 0: logging.info("FTP: dup read reply at %u of len %u ofs=%u", op.offset, op.size, self.fh.tell()) self.duplicates += 1 - return MAVFTPReturn('BurstReadFile', ERR_Fail) + return MAVFTPReturn("BurstReadFile", ERR_Fail) self.__write_payload(op) self.fh.seek(ofs) if self.__check_read_finished(): - return MAVFTPReturn('BurstReadFile', ERR_None) + return MAVFTPReturn("BurstReadFile", ERR_None) elif op.offset > ofs: # we have a gap - gap = (ofs, op.offset-ofs) + gap = (ofs, op.offset - ofs) max_read = self.burst_size while True: if gap[1] <= max_read: @@ -613,13 +639,17 @@ def __handle_burst_read(self, op, _m) -> MAVFTPReturn: # pylint: disable=too-ma # a burst complete with non-zero size and less than burst packet size # means EOF if not self.reached_eof and self.ftp_settings.debug > 0: - logging.info("FTP: EOF at %u with %u gaps t=%.2f", self.fh.tell(), - len(self.read_gaps), time.time() - self.op_start) + logging.info( + "FTP: EOF at %u with %u gaps t=%.2f", + self.fh.tell(), + len(self.read_gaps), + time.time() - self.op_start, + ) self.reached_eof = True if self.__check_read_finished(): - return MAVFTPReturn('BurstReadFile', ERR_None) + return MAVFTPReturn("BurstReadFile", ERR_None) self.__check_read_send() - return MAVFTPReturn('BurstReadFile', ERR_None) + return MAVFTPReturn("BurstReadFile", ERR_None) more = self.last_op more.offset = op.offset + op.size if self.ftp_settings.debug > 0: @@ -632,31 +662,32 @@ def __handle_burst_read(self, op, _m) -> MAVFTPReturn: # pylint: disable=too-ma # we lost the last part of the burst if self.ftp_settings.debug > 0: logging.error("FTP: burst lost EOF %u %u", self.fh.tell(), op.offset) - return MAVFTPReturn('BurstReadFile', ERR_Fail) + return MAVFTPReturn("BurstReadFile", ERR_Fail) if not self.reached_eof and self.ftp_settings.debug > 0: - logging.info("FTP: EOF at %u with %u gaps t=%.2f", self.fh.tell(), - len(self.read_gaps), time.time() - self.op_start) + logging.info( + "FTP: EOF at %u with %u gaps t=%.2f", self.fh.tell(), len(self.read_gaps), time.time() - self.op_start + ) self.reached_eof = True if self.__check_read_finished(): - return MAVFTPReturn('BurstReadFile', ERR_None) + return MAVFTPReturn("BurstReadFile", ERR_None) self.__check_read_send() elif self.ftp_settings.debug > 0: logging.info("FTP: burst Nack (ecode:%u): %s", ecode, op) - return MAVFTPReturn('BurstReadFile', ERR_Fail) + return MAVFTPReturn("BurstReadFile", ERR_Fail) if self.ftp_settings.debug > 0: logging.error("FTP: burst nack: %s", op) - return MAVFTPReturn('BurstReadFile', ERR_Fail) + return MAVFTPReturn("BurstReadFile", ERR_Fail) else: logging.warning("FTP: burst error: %s", op) - return MAVFTPReturn('BurstReadFile', ERR_Fail) + return MAVFTPReturn("BurstReadFile", ERR_Fail) def __handle_reply_read(self, op, _m) -> MAVFTPReturn: - '''handle OP_ReadFile reply''' + """handle OP_ReadFile reply""" if self.fh is None or self.filename is None: if self.ftp_settings.debug > 0: logging.warning("FTP: Unexpected read reply") logging.warning(op) - return MAVFTPReturn('ReadFile', ERR_Fail) + return MAVFTPReturn("ReadFile", ERR_Fail) if self.backlog > 0: self.backlog -= 1 if op.opcode == OP_Ack and self.fh is not None: @@ -670,9 +701,9 @@ def __handle_reply_read(self, op, _m) -> MAVFTPReturn: if self.ftp_settings.debug > 0: logging.info("FTP: removed gap %u, %u, %u", gap, self.reached_eof, len(self.read_gaps)) if self.__check_read_finished(): - return MAVFTPReturn('ReadFile', ERR_None) + return MAVFTPReturn("ReadFile", ERR_None) elif op.size < self.burst_size: - logging.info("FTP: file size changed to %u", op.offset+op.size) + logging.info("FTP: file size changed to %u", op.offset + op.size) self.__terminate_session() else: self.duplicates += 1 @@ -682,10 +713,10 @@ def __handle_reply_read(self, op, _m) -> MAVFTPReturn: logging.info("FTP: Read failed with %u gaps %s", len(self.read_gaps), str(op)) self.__terminate_session() self.__check_read_send() - return MAVFTPReturn('ReadFile', ERR_None) + return MAVFTPReturn("ReadFile", ERR_None) def cmd_put(self, args, fh=None, callback=None, progress_callback=None) -> MAVFTPReturn: - '''put file''' + """put file""" if len(args) == 0 or len(args) > 2: logging.error("Usage: put [FILENAME ]") return MAVFTPReturn("CreateFile", ERR_InvalidArguments) @@ -696,7 +727,7 @@ def cmd_put(self, args, fh=None, callback=None, progress_callback=None) -> MAVFT self.fh = fh if self.fh is None: try: - self.fh = open(fname, 'rb') # pylint: disable=consider-using-with + self.fh = open(fname, "rb") # pylint: disable=consider-using-with except Exception as ex: # pylint: disable=broad-exception-caught logging.error("FTP: Failed to open %s: %s", fname, ex) return MAVFTPReturn("CreateFile", ERR_FailToOpenLocalFile) @@ -708,7 +739,7 @@ def cmd_put(self, args, fh=None, callback=None, progress_callback=None) -> MAVFT self.filename += os.path.basename(fname) if callback is None: logging.info("Putting %s to %s", fname, self.filename) - self.fh.seek(0,2) + self.fh.seek(0, 2) file_size = self.fh.tell() self.fh.seek(0) @@ -732,13 +763,13 @@ def cmd_put(self, args, fh=None, callback=None, progress_callback=None) -> MAVFT self.put_callback_progress = progress_callback self.read_retries = 0 self.op_start = time.time() - enc_fname = bytearray(self.filename, 'ascii') + enc_fname = bytearray(self.filename, "ascii") op = FTP_OP(self.seq, self.session, OP_CreateFile, len(enc_fname), 0, 0, 0, enc_fname) self.__send(op) return MAVFTPReturn("CreateFile", ERR_None) def __put_finished(self, flen): - '''finish a put''' + """finish a put""" if self.put_callback_progress: self.put_callback_progress(1.0) self.put_callback_progress = None @@ -751,20 +782,20 @@ def __put_finished(self, flen): logging.info("Put %u bytes to %s file in %.2fs %.1fkByte/s", flen, self.filename, dt, rate) def __handle_create_file_reply(self, op, _m) -> MAVFTPReturn: - '''handle OP_CreateFile reply''' + """handle OP_CreateFile reply""" if self.fh is None: self.__terminate_session() - return MAVFTPReturn('CreateFile', ERR_FileNotFound) + return MAVFTPReturn("CreateFile", ERR_FileNotFound) if op.opcode == OP_Ack: self.__send_more_writes() else: ret = self.__decode_ftp_ack_and_nack(op) self.__terminate_session() return ret - return MAVFTPReturn('CreateFile', ERR_None) + return MAVFTPReturn("CreateFile", ERR_None) def __send_more_writes(self): - '''send some more writes''' + """send some more writes""" if len(self.write_list) == 0: # all done self.__put_finished(self.write_file_size) @@ -773,11 +804,11 @@ def __send_more_writes(self): now = time.time() if self.write_last_send is not None: - if now - self.write_last_send > max(min(10*self.rtt, 1),0.2): + if now - self.write_last_send > max(min(10 * self.rtt, 1), 0.2): # we seem to have lost a block of replies - self.write_pending = max(0, self.write_pending-1) + self.write_pending = max(0, self.write_pending - 1) - n = min(self.ftp_settings.write_qsize-self.write_pending, len(self.write_list)) + n = min(self.ftp_settings.write_qsize - self.write_pending, len(self.write_list)) for _i in range(n): # send in round-robin, skipping any that have been acked idx = self.write_idx @@ -793,14 +824,14 @@ def __send_more_writes(self): self.write_last_send = now def __handle_write_reply(self, op, _m) -> MAVFTPReturn: - '''handle OP_WriteFile reply''' + """handle OP_WriteFile reply""" if self.fh is None: self.__terminate_session() - return MAVFTPReturn('WriteFile', ERR_FileNotFound) + return MAVFTPReturn("WriteFile", ERR_FileNotFound) if op.opcode != OP_Ack: logging.error("FTP: Write failed") self.__terminate_session() - return MAVFTPReturn('WriteFile', ERR_FileProtected) + return MAVFTPReturn("WriteFile", ERR_FileProtected) # assume the FTP server processes the blocks sequentially. This means # when we receive an ack that any blocks between the last ack and this @@ -813,75 +844,75 @@ def __handle_write_reply(self, op, _m) -> MAVFTPReturn: self.write_list.discard(idx) self.write_acks += 1 if self.put_callback_progress: - self.put_callback_progress(self.write_acks/float(self.write_total)) + self.put_callback_progress(self.write_acks / float(self.write_total)) self.__send_more_writes() - return MAVFTPReturn('WriteFile', ERR_None) + return MAVFTPReturn("WriteFile", ERR_None) def cmd_rm(self, args) -> MAVFTPReturn: - '''remove file''' + """remove file""" if len(args) != 1: logging.error("Usage: rm [FILENAME]") return MAVFTPReturn("RemoveFile", ERR_InvalidArguments) fname = args[0] logging.info("Removing file %s", fname) - enc_fname = bytearray(fname, 'ascii') + enc_fname = bytearray(fname, "ascii") op = FTP_OP(self.seq, self.session, OP_RemoveFile, len(enc_fname), 0, 0, 0, enc_fname) self.__send(op) - return self.process_ftp_reply('RemoveFile') + return self.process_ftp_reply("RemoveFile") def cmd_rmdir(self, args): - '''remove directory''' + """remove directory""" if len(args) != 1: logging.error("Usage: rmdir [DIRECTORYNAME]") return MAVFTPReturn("RemoveDirectory", ERR_InvalidArguments) dname = args[0] logging.info("Removing directory %s", dname) - enc_dname = bytearray(dname, 'ascii') + enc_dname = bytearray(dname, "ascii") op = FTP_OP(self.seq, self.session, OP_RemoveDirectory, len(enc_dname), 0, 0, 0, enc_dname) self.__send(op) - return self.process_ftp_reply('RemoveDirectory') + return self.process_ftp_reply("RemoveDirectory") def __handle_remove_reply(self, op, _m): - '''handle remove reply''' + """handle remove reply""" return self.__decode_ftp_ack_and_nack(op) def cmd_rename(self, args) -> MAVFTPReturn: - '''rename file or directory''' + """rename file or directory""" if len(args) < 2: logging.error("Usage: rename [OLDNAME NEWNAME]") return MAVFTPReturn("Rename", ERR_InvalidArguments) name1 = args[0] name2 = args[1] logging.info("Renaming %s to %s", name1, name2) - enc_name1 = bytearray(name1, 'ascii') - enc_name2 = bytearray(name2, 'ascii') - enc_both = enc_name1 + b'\x00' + enc_name2 + enc_name1 = bytearray(name1, "ascii") + enc_name2 = bytearray(name2, "ascii") + enc_both = enc_name1 + b"\x00" + enc_name2 op = FTP_OP(self.seq, self.session, OP_Rename, len(enc_both), 0, 0, 0, enc_both) self.__send(op) - return self.process_ftp_reply('Rename') + return self.process_ftp_reply("Rename") def __handle_rename_reply(self, op, _m): - '''handle rename reply''' + """handle rename reply""" return self.__decode_ftp_ack_and_nack(op) def cmd_mkdir(self, args) -> MAVFTPReturn: - '''make directory''' + """make directory""" if len(args) != 1: logging.error("Usage: mkdir NAME") return MAVFTPReturn("CreateDirectory", ERR_InvalidArguments) name = args[0] logging.info("Creating directory %s", name) - enc_name = bytearray(name, 'ascii') + enc_name = bytearray(name, "ascii") op = FTP_OP(self.seq, self.session, OP_CreateDirectory, len(enc_name), 0, 0, 0, enc_name) self.__send(op) - return self.process_ftp_reply('CreateDirectory') + return self.process_ftp_reply("CreateDirectory") def __handle_mkdir_reply(self, op, _m): - '''handle mkdir reply''' + """handle mkdir reply""" return self.__decode_ftp_ack_and_nack(op) def cmd_crc(self, args) -> MAVFTPReturn: - '''get file crc''' + """get file crc""" if len(args) != 1: logging.error("Usage: crc [NAME]") return MAVFTPReturn("CalcFileCRC32", ERR_InvalidArguments) @@ -889,45 +920,50 @@ def cmd_crc(self, args) -> MAVFTPReturn: self.filename = name self.op_start = time.time() logging.info("Getting CRC for %s", name) - enc_name = bytearray(name, 'ascii') + enc_name = bytearray(name, "ascii") op = FTP_OP(self.seq, self.session, OP_CalcFileCRC32, len(enc_name), 0, 0, 0, bytearray(enc_name)) self.__send(op) - return self.process_ftp_reply('CalcFileCRC32') + return self.process_ftp_reply("CalcFileCRC32") def __handle_crc_reply(self, op, _m): - '''handle crc reply''' + """handle crc reply""" if op.opcode == OP_Ack and op.size == 4: - crc, = struct.unpack(" MAVFTPReturn: - '''cancel any pending op''' + """cancel any pending op""" self.__terminate_session() return MAVFTPReturn("TerminateSession", ERR_None) def cmd_status(self) -> MAVFTPReturn: - '''show status''' + """show status""" if self.fh is None: logging.info("No transfer in progress") else: ofs = self.fh.tell() dt = time.time() - self.op_start rate = (ofs / dt) / 1024.0 - logging.info("Transfer at offset %u with %u gaps %u retries %.1f kByte/sec", - ofs, len(self.read_gaps), self.read_retries, rate) + logging.info( + "Transfer at offset %u with %u gaps %u retries %.1f kByte/sec", + ofs, + len(self.read_gaps), + self.read_retries, + rate, + ) return MAVFTPReturn("Status", ERR_None) def __op_parse(self, m): - '''parse a FILE_TRANSFER_PROTOCOL msg''' + """parse a FILE_TRANSFER_PROTOCOL msg""" hdr = bytearray(m.payload[0:12]) (seq, session, opcode, size, req_opcode, burst_complete, _pad, offset) = struct.unpack(" MAVFTPReturn: # pylint: disable=too-many-branches, too-many-return-statements - '''handle a mavlink packet''' + """handle a mavlink packet""" operation_name = "mavlink_packet" mtype = m.get_type() if mtype != "FILE_TRANSFER_PROTOCOL": @@ -935,8 +971,9 @@ def __mavlink_packet(self, m) -> MAVFTPReturn: # pylint: disable=too-many-branc return MAVFTPReturn(operation_name, ERR_Fail) if m.target_system != self.master.source_system or m.target_component != self.master.source_component: - logging.info("FTP: wrong MAVLink target %u component %u. Will discard message", - m.target_system, m.target_component) + logging.info( + "FTP: wrong MAVLink target %u component %u. Will discard message", m.target_system, m.target_component + ) return MAVFTPReturn(operation_name, ERR_Fail) op = self.__op_parse(m) @@ -946,8 +983,7 @@ def __mavlink_packet(self, m) -> MAVFTPReturn: # pylint: disable=too-many-branc logging.info("FTP: < %s dt=%.2f", op, dt) if op.session != self.session: if self.ftp_settings.debug > 0: - logging.warning("FTP: wrong session replied %u expected %u. Will discard message", - op.session, self.session) + logging.warning("FTP: wrong session replied %u expected %u. Will discard message", op.session, self.session) return MAVFTPReturn(operation_name, ERR_InvalidSession) self.last_op_time = now if self.ftp_settings.pkt_loss_rx > 0: @@ -984,11 +1020,11 @@ def __mavlink_packet(self, m) -> MAVFTPReturn: # pylint: disable=too-many-branc if op.req_opcode == OP_CalcFileCRC32: return self.__handle_crc_reply(op, m) - logging.info('FTP Unknown %s', str(op)) + logging.info("FTP Unknown %s", str(op)) return MAVFTPReturn(operation_name, ERR_InvalidOpcode) def __send_gap_read(self, g): - '''send a read for a gap''' + """send a read for a gap""" (offset, length) = g if self.ftp_settings.debug > 0: logging.info("FTP: Gap read of %u at %u rem=%u blog=%u", length, offset, len(self.read_gaps), self.backlog) @@ -1001,7 +1037,7 @@ def __send_gap_read(self, g): self.backlog += 1 def __check_read_send(self): - '''see if we should send another gap read''' + """see if we should send another gap read""" if len(self.read_gaps) == 0: return g = self.read_gaps[0] @@ -1030,14 +1066,18 @@ def __check_read_send(self): self.__send_gap_read(g) def __idle_task(self) -> bool: - '''check for file gaps and lost requests''' + """check for file gaps and lost requests""" now = time.time() - assert self.ftp_settings.idle_detection_time > self.ftp_settings.read_retry_time, \ - "settings.idle_detection_time must be > settings.read_retry_time" + assert ( + self.ftp_settings.idle_detection_time > self.ftp_settings.read_retry_time + ), "settings.idle_detection_time must be > settings.read_retry_time" # see if we lost an open reply - if self.op_start is not None and now - self.op_start > self.ftp_settings.read_retry_time and \ - self.last_op.opcode == OP_OpenFileRO: + if ( + self.op_start is not None + and now - self.op_start > self.ftp_settings.read_retry_time + and self.last_op.opcode == OP_OpenFileRO + ): self.op_start = now self.open_retries += 1 if self.open_retries > 2: @@ -1060,8 +1100,11 @@ def __idle_task(self) -> bool: return self.__last_send_time_was_more_than_idle_detection_time_ago(now) # see if burst read has stalled - if not self.reached_eof and self.last_burst_read is not None and \ - now - self.last_burst_read > self.ftp_settings.retry_time: + if ( + not self.reached_eof + and self.last_burst_read is not None + and now - self.last_burst_read > self.ftp_settings.retry_time + ): dt = now - self.last_burst_read self.last_burst_read = now if self.ftp_settings.debug > 0: @@ -1081,24 +1124,24 @@ def __last_send_time_was_more_than_idle_detection_time_ago(self, now: float) -> return self.last_send_time is not None and now - self.last_send_time > self.ftp_settings.idle_detection_time def __handle_reset_sessions_reply(self, op, _m): - '''handle reset sessions reply''' + """handle reset sessions reply""" return self.__decode_ftp_ack_and_nack(op) def process_ftp_reply(self, operation_name, timeout=5) -> MAVFTPReturn: - ''' execute an FTP operation that requires processing a MAVLink response''' + """execute an FTP operation that requires processing a MAVLink response""" start_time = time.time() ret = MAVFTPReturn(operation_name, ERR_Fail) recv_timeout = 0.1 - assert timeout == 0 or timeout > self.ftp_settings.idle_detection_time, \ - "timeout must be > settings.idle_detection_time" - assert recv_timeout < self.ftp_settings.retry_time, \ - "recv_timeout must be < settings.retry_time" + assert ( + timeout == 0 or timeout > self.ftp_settings.idle_detection_time + ), "timeout must be > settings.idle_detection_time" + assert recv_timeout < self.ftp_settings.retry_time, "recv_timeout must be < settings.retry_time" while True: # an FTP operation can have multiple responses - m = self.master.recv_match(type=['FILE_TRANSFER_PROTOCOL'], timeout=recv_timeout) + m = self.master.recv_match(type=["FILE_TRANSFER_PROTOCOL"], timeout=recv_timeout) if m is not None: if operation_name == "TerminateSession": - #self.silently_discard_terminate_session_reply() + # self.silently_discard_terminate_session_reply() ret = MAVFTPReturn(operation_name, ERR_None) else: ret = self.__mavlink_packet(m) @@ -1110,8 +1153,8 @@ def process_ftp_reply(self, operation_name, timeout=5) -> MAVFTPReturn: break return ret - def __decode_ftp_ack_and_nack(self, op: FTP_OP, operation_name: str='') -> MAVFTPReturn: - '''decode FTP Acknowledge reply''' + def __decode_ftp_ack_and_nack(self, op: FTP_OP, operation_name: str = "") -> MAVFTPReturn: + """decode FTP Acknowledge reply""" system_error = 0 invalid_error_code = 0 operation_name_dict = { @@ -1148,9 +1191,17 @@ def __decode_ftp_ack_and_nack(self, op: FTP_OP, operation_name: str='') -> MAVFT error_code = ERR_NoErrorCodeInNack elif error_code == ERR_FailErrno: error_code = ERR_NoFilesystemErrorInPayload - elif error_code not in [ERR_Fail, ERR_InvalidDataSize, ERR_InvalidSession, ERR_NoSessionsAvailable, - ERR_EndOfFile, ERR_UnknownCommand, ERR_FileExists, ERR_FileProtected, - ERR_FileNotFound]: + elif error_code not in [ + ERR_Fail, + ERR_InvalidDataSize, + ERR_InvalidSession, + ERR_NoSessionsAvailable, + ERR_EndOfFile, + ERR_UnknownCommand, + ERR_FileExists, + ERR_FileProtected, + ERR_FileNotFound, + ]: invalid_error_code = error_code error_code = ERR_InvalidErrorCode elif op.payload[0] == ERR_FailErrno and len_payload == 2: @@ -1160,16 +1211,22 @@ def __decode_ftp_ack_and_nack(self, op: FTP_OP, operation_name: str='') -> MAVFT error_code = ERR_PayloadTooLarge else: error_code = ERR_InvalidOpcode - return MAVFTPReturn(op_ret_name, error_code, system_error=system_error, invalid_error_code=invalid_error_code, - invalid_payload_size=len_payload, invalid_opcode=op.opcode) + return MAVFTPReturn( + op_ret_name, + error_code, + system_error=system_error, + invalid_error_code=invalid_error_code, + invalid_payload_size=len_payload, + invalid_opcode=op.opcode, + ) @staticmethod def ftp_param_decode(data): # pylint: disable=too-many-locals - '''decode parameter data, returning ParamData''' + """decode parameter data, returning ParamData""" pdata = ParamData() - magic = 0x671b - magic_defaults = 0x671c + magic = 0x671B + magic_defaults = 0x671C if len(data) < 6: logging.error("paramftp: Not enough data do decode, only %u bytes", len(data)) return None @@ -1182,10 +1239,10 @@ def ftp_param_decode(data): # pylint: disable=too-many-locals # mapping of data type to type length and format data_types = { - 1: (1, 'b'), - 2: (2, 'h'), - 3: (4, 'i'), - 4: (4, 'f'), + 1: (1, "b"), + 2: (2, "h"), + 3: (4, "i"), + 4: (4, "f"), } count = 0 @@ -1212,21 +1269,24 @@ def ftp_param_decode(data): # pylint: disable=too-many-locals name_len = ((plen >> 4) & 0x0F) + 1 common_len = plen & 0x0F - name = last_name[0:common_len] + data[2:2+name_len] - vdata = data[2+name_len:2+name_len+type_len+default_len] + name = last_name[0:common_len] + data[2 : 2 + name_len] + vdata = data[2 + name_len : 2 + name_len + type_len + default_len] last_name = name - data = data[2+name_len+type_len+default_len:] + data = data[2 + name_len + type_len + default_len :] if with_defaults: if has_default: - v1, v2, = struct.unpack("<" + type_format + type_format, vdata) + ( + v1, + v2, + ) = struct.unpack("<" + type_format + type_format, vdata) pdata.add_param(name, v1, ptype) pdata.add_default(name, v2, ptype) else: - v, = struct.unpack("<" + type_format, vdata) + (v,) = struct.unpack("<" + type_format, vdata) pdata.add_param(name, v, ptype) pdata.add_default(name, v, ptype) else: - v, = struct.unpack("<" + type_format, vdata) + (v,) = struct.unpack("<" + type_format, vdata) pdata.add_param(name, v, ptype) count += 1 @@ -1245,11 +1305,11 @@ def missionplanner_sort(item: str) -> Tuple[str, ...]: @staticmethod def extract_params(pdata, sort_type) -> Dict[str, Tuple[float, str]]: - ''' extract parameter values to an optionally sorted dictionary of name->(value, type)''' + """extract parameter values to an optionally sorted dictionary of name->(value, type)""" pdict = {} if pdata: - for (name, value, ptype) in pdata: - pdict[name.decode('utf-8')] = (value, ptype) + for name, value, ptype in pdata: + pdict[name.decode("utf-8")] = (value, ptype) if sort_type == "missionplanner": pdict = dict(sorted(pdict.items(), key=lambda x: MAVFTP.missionplanner_sort(x[0]))) # sort alphabetically @@ -1260,17 +1320,22 @@ def extract_params(pdata, sort_type) -> Dict[str, Tuple[float, str]]: return pdict @staticmethod - def save_params(pdict: Dict[str, Tuple[float, str]], filename: str, sort_type: str, - add_datatype_comments: bool, add_timestamp_comment: bool) -> None: - '''Save Ardupilot parameter information to a local file''' + def save_params( + pdict: Dict[str, Tuple[float, str]], + filename: str, + sort_type: str, + add_datatype_comments: bool, + add_timestamp_comment: bool, + ) -> None: + """Save Ardupilot parameter information to a local file""" if not pdict: return - with open(filename, 'w', encoding='utf-8') as f: + with open(filename, "w", encoding="utf-8") as f: parameter_data_types = { - 1: '8-bit', - 2: '16-bit', - 3: '32-bit integer', - 4: '32-bit float', + 1: "8-bit", + 2: "16-bit", + 3: "32-bit integer", + 4: "32-bit float", } if add_timestamp_comment: f.write(f"# Parameters saved at {datetime.now().strftime('%Y-%m-%d %H:%M:%S')}\n") @@ -1285,10 +1350,15 @@ def save_params(pdict: Dict[str, Tuple[float, str]], filename: str, sort_type: s f.write("\n") logging.info("Outputted %u parameters to %s", len(pdict), filename) - - def cmd_getparams(self, args, progress_callback=None, sort_type: str="missionplanner", # pylint: disable=too-many-arguments - add_datatype_comments: bool=False, add_timestamp_comment: bool=False): - ''' Decode the parameter file and save the values and defaults to disk ''' + def cmd_getparams( # pylint: disable=too-many-arguments + self, + args, + progress_callback=None, + sort_type: str = "missionplanner", + add_datatype_comments: bool = False, + add_timestamp_comment: bool = False, + ): + """Decode the parameter file and save the values and defaults to disk""" def decode_and_save_params(fh): if fh is None: @@ -1319,9 +1389,11 @@ def decode_and_save_params(fh): else: logging.info("%-16s %f", name, value) - self.cmd_get(['@PARAM/param.pck?withdefaults=1' if len(args) > 1 else '@PARAM/param.pck'], - callback=decode_and_save_params, - progress_callback=progress_callback) + self.cmd_get( + ["@PARAM/param.pck?withdefaults=1" if len(args) > 1 else "@PARAM/param.pck"], + callback=decode_and_save_params, + progress_callback=progress_callback, + ) if __name__ == "__main__": @@ -1332,194 +1404,147 @@ def argument_parser(): This function sets up an argument parser to handle the command-line arguments for the script. """ - parser = ArgumentParser(description='MAVFTP - MAVLink File Transfer Protocol https://mavlink.io/en/services/ftp.html' - ' A tool to do file operations between a ground control station and a drone using the MAVLink' - ' protocol.') - parser.add_argument("--baudrate", type=int, default=115200, - help="master port baud rate. Defaults to %(default)s") - parser.add_argument("--device", type=str, default='', - help="serial device. For windows use COMx where x is the port number. " - "For Unix use /dev/ttyUSBx where x is the port number. Defaults to autodetection") - parser.add_argument("--source-system", type=int, default=250, - help='MAVLink source system for this GCS. Defaults to %(default)s') - parser.add_argument("--loglevel", default="INFO", - help="log level. Defaults to %(default)s") + parser = ArgumentParser( + description="MAVFTP - MAVLink File Transfer Protocol https://mavlink.io/en/services/ftp.html" + " A tool to do file operations between a ground control station and a drone using the MAVLink" + " protocol." + ) + parser.add_argument("--baudrate", type=int, default=115200, help="master port baud rate. Defaults to %(default)s") + parser.add_argument( + "--device", + type=str, + default="", + help="serial device. For windows use COMx where x is the port number. " + "For Unix use /dev/ttyUSBx where x is the port number. Defaults to autodetection", + ) + parser.add_argument( + "--source-system", type=int, default=250, help="MAVLink source system for this GCS. Defaults to %(default)s" + ) + parser.add_argument("--loglevel", default="INFO", help="log level. Defaults to %(default)s") # MAVFTP settings - parser.add_argument("--debug", type=int, default=0, choices=[0, 1, 2], - help="Debug level 0 for none, 2 for max verbosity. Defaults to %(default)s") - parser.add_argument("--pkt_loss_tx", type=int, default=0, - help="Packet loss on TX. Defaults to %(default)s") - parser.add_argument("--pkt_loss_rx", type=int, default=0, - help="Packet loss on RX. Defaults to %(default)s") - parser.add_argument("--max_backlog", type=int, default=5, - help="Max backlog. Defaults to %(default)s") - parser.add_argument("--burst_read_size", type=int, default=80, - help="Burst read size. Defaults to %(default)s") - parser.add_argument("--write_size", type=int, default=80, - help="Write size. Defaults to %(default)s") - parser.add_argument("--write_qsize", type=int, default=5, - help="Write queue size. Defaults to %(default)s") - parser.add_argument("--idle_detection_time", type=float, default=1.2, - help="Idle detection time. Defaults to %(default)s") - parser.add_argument("--read_retry_time", type=float, default=1.0, - help="Read retry time. Defaults to %(default)s") - parser.add_argument("--retry_time", type=float, default=0.5, - help="Retry time. Defaults to %(default)s") + parser.add_argument( + "--debug", + type=int, + default=0, + choices=[0, 1, 2], + help="Debug level 0 for none, 2 for max verbosity. Defaults to %(default)s", + ) + parser.add_argument("--pkt_loss_tx", type=int, default=0, help="Packet loss on TX. Defaults to %(default)s") + parser.add_argument("--pkt_loss_rx", type=int, default=0, help="Packet loss on RX. Defaults to %(default)s") + parser.add_argument("--max_backlog", type=int, default=5, help="Max backlog. Defaults to %(default)s") + parser.add_argument("--burst_read_size", type=int, default=80, help="Burst read size. Defaults to %(default)s") + parser.add_argument("--write_size", type=int, default=80, help="Write size. Defaults to %(default)s") + parser.add_argument("--write_qsize", type=int, default=5, help="Write queue size. Defaults to %(default)s") + parser.add_argument( + "--idle_detection_time", type=float, default=1.2, help="Idle detection time. Defaults to %(default)s" + ) + parser.add_argument("--read_retry_time", type=float, default=1.0, help="Read retry time. Defaults to %(default)s") + parser.add_argument("--retry_time", type=float, default=0.5, help="Retry time. Defaults to %(default)s") subparsers = parser.add_subparsers(dest="command", required=True) # Get command - parser_get = subparsers.add_parser( - 'get', - help='Get a file from the remote flight controller.') + parser_get = subparsers.add_parser("get", help="Get a file from the remote flight controller.") parser_get.add_argument( - 'arg1', - type=str, - metavar='remote_path', - help='Path to the file on the remote flight controller.') + "arg1", type=str, metavar="remote_path", help="Path to the file on the remote flight controller." + ) parser_get.add_argument( - 'arg2', - nargs='?', - type=str, - metavar='local_path', - help='Optional local path to save the file.') + "arg2", nargs="?", type=str, metavar="local_path", help="Optional local path to save the file." + ) # Getparams command parser_getparams = subparsers.add_parser( - 'getparams', - help='Get and decode parameters from the remote flight controller.') + "getparams", help="Get and decode parameters from the remote flight controller." + ) parser_getparams.add_argument( - 'arg1', - type=str, - metavar='param_values_path', - help='Local path to save the parameter values file to.') + "arg1", type=str, metavar="param_values_path", help="Local path to save the parameter values file to." + ) parser_getparams.add_argument( - 'arg2', - nargs='?', + "arg2", + nargs="?", type=str, - metavar='param_defaults_path', - help='Optional local path to save the parameter defaults file to.') + metavar="param_defaults_path", + help="Optional local path to save the parameter defaults file to.", + ) parser_getparams.add_argument( - '-s', '--sort', - choices=['none', 'missionplanner', 'mavproxy'], - default='missionplanner', - help='Sort the parameters in the file. Defaults to %(default)s.', - ) + "-s", + "--sort", + choices=["none", "missionplanner", "mavproxy"], + default="missionplanner", + help="Sort the parameters in the file. Defaults to %(default)s.", + ) parser_getparams.add_argument( - '-dtc', '--add_datatype_comments', - action='store_true', + "-dtc", + "--add_datatype_comments", + action="store_true", default=False, - help='Add parameter datatype type comments to the outputted parameter files. Defaults to %(default)s.', - ) + help="Add parameter datatype type comments to the outputted parameter files. Defaults to %(default)s.", + ) parser_getparams.add_argument( - '-t', '--add_timestamp_comment', - action='store_true', + "-t", + "--add_timestamp_comment", + action="store_true", default=False, - help='Add timestamp comment at the top of the file. Defaults to %(default)s.', - ) + help="Add timestamp comment at the top of the file. Defaults to %(default)s.", + ) # Put command - parser_put = subparsers.add_parser( - 'put', - help='Put a file to the remote flight controller.') + parser_put = subparsers.add_parser("put", help="Put a file to the remote flight controller.") parser_put.add_argument( - 'arg1', - type=str, - metavar='local_path', - help='Local path to the file to upload to the flight controller.') + "arg1", type=str, metavar="local_path", help="Local path to the file to upload to the flight controller." + ) parser_put.add_argument( - 'arg2', - nargs='?', + "arg2", + nargs="?", type=str, - metavar='remote_path', - help='Optional remote path where the file should be uploaded on the remote flight controller.') + metavar="remote_path", + help="Optional remote path where the file should be uploaded on the remote flight controller.", + ) # List command - parser_list = subparsers.add_parser( - 'list', - help='List files in a directory on the remote flight controller.') - parser_list.add_argument( - 'arg1', - nargs='?', - type=str, - metavar='remote_path', - help='Optional path to list files from.') + parser_list = subparsers.add_parser("list", help="List files in a directory on the remote flight controller.") + parser_list.add_argument("arg1", nargs="?", type=str, metavar="remote_path", help="Optional path to list files from.") # Mkdir command - parser_mkdir = subparsers.add_parser( - 'mkdir', - help='Create a directory on the remote flight controller.') - parser_mkdir.add_argument( - 'arg1', - type=str, - metavar='remote_path', - help='Path to the directory to create.') + parser_mkdir = subparsers.add_parser("mkdir", help="Create a directory on the remote flight controller.") + parser_mkdir.add_argument("arg1", type=str, metavar="remote_path", help="Path to the directory to create.") # Rmdir command - parser_rmdir = subparsers.add_parser( - 'rmdir', - help='Remove a directory on the remote flight controller.') - parser_rmdir.add_argument( - 'arg1', - type=str, - metavar='remote_path', - help='Path to the directory to remove.') + parser_rmdir = subparsers.add_parser("rmdir", help="Remove a directory on the remote flight controller.") + parser_rmdir.add_argument("arg1", type=str, metavar="remote_path", help="Path to the directory to remove.") # Rm command - parser_rm = subparsers.add_parser( - 'rm', - help='Remove a file on the remote flight controller.') - parser_rm.add_argument( - 'arg1', - type=str, - metavar='remote_path', - help='Path to the file to remove.') + parser_rm = subparsers.add_parser("rm", help="Remove a file on the remote flight controller.") + parser_rm.add_argument("arg1", type=str, metavar="remote_path", help="Path to the file to remove.") # Rename command - parser_rename = subparsers.add_parser( - 'rename', - help='Rename a file or directory on the remote flight controller.') - parser_rename.add_argument( - 'arg1', - type=str, - metavar='old_remote_path', - help='Current path of the file/directory.') - parser_rename.add_argument( - 'new_remote_path', - type=str, - metavar='arg2', - help='New path for the file/directory.') + parser_rename = subparsers.add_parser("rename", help="Rename a file or directory on the remote flight controller.") + parser_rename.add_argument("arg1", type=str, metavar="old_remote_path", help="Current path of the file/directory.") + parser_rename.add_argument("new_remote_path", type=str, metavar="arg2", help="New path for the file/directory.") # CRC command - parser_crc = subparsers.add_parser( - 'crc', - help='Calculate the CRC of a file on the remote flight controller.') - parser_crc.add_argument( - 'arg1', - type=str, - metavar='remote_path', - help='Path to the file to calculate the CRC of.') + parser_crc = subparsers.add_parser("crc", help="Calculate the CRC of a file on the remote flight controller.") + parser_crc.add_argument("arg1", type=str, metavar="remote_path", help="Path to the file to calculate the CRC of.") # Add other subparsers commands as needed return parser.parse_args() - def auto_detect_serial(): preferred_ports = [ - '*FTDI*', + "*FTDI*", "*3D*", "*USB_to_UART*", - '*Ardu*', - '*PX4*', - '*Hex_*', - '*Holybro_*', - '*mRo*', - '*FMU*', - '*Swift-Flyer*', - '*Serial*', - '*CubePilot*', - '*Qiotek*', + "*Ardu*", + "*PX4*", + "*Hex_*", + "*Holybro_*", + "*mRo*", + "*FMU*", + "*Swift-Flyer*", + "*Serial*", + "*CubePilot*", + "*Qiotek*", ] serial_list = mavutil.auto_detect_serial(preferred_list=preferred_ports) serial_list.sort(key=lambda x: x.device) @@ -1531,7 +1556,6 @@ def auto_detect_serial(): return serial_list - def auto_connect(device): comport = None if device: @@ -1540,7 +1564,7 @@ def auto_connect(device): autodetect_serial = auto_detect_serial() if autodetect_serial: # Resolve the soft link if it's a Linux system - if os.name == 'posix': + if os.name == "posix": try: dev = autodetect_serial[0].device logging.debug("Auto-detected device %s", dev) @@ -1551,26 +1575,24 @@ def auto_connect(device): autodetect_serial[0].device = resolved_path logging.debug("Resolved soft link %s to %s", dev, resolved_path) except OSError: - pass # Not a soft link, proceed with the original device path + pass # Not a soft link, proceed with the original device path comport = autodetect_serial[0] else: logging.error("No serial ports found. Please connect a flight controller and try again.") sys.exit(1) return comport - def wait_heartbeat(m): - '''wait for a heartbeat so we know the target system IDs''' + """wait for a heartbeat so we know the target system IDs""" logging.info("Waiting for flight controller heartbeat") m.wait_heartbeat(timeout=5) logging.info("Heartbeat from system %u, component %u", m.target_system, m.target_system) - def main(): - '''for testing/example purposes only''' + """for testing/example purposes only""" args = argument_parser() - logging.basicConfig(level=logging.getLevelName(args.loglevel), format='%(levelname)s - %(message)s') + logging.basicConfig(level=logging.getLevelName(args.loglevel), format="%(levelname)s - %(message)s") # create a mavlink serial instance comport = auto_connect(args.device) @@ -1580,31 +1602,33 @@ def main(): wait_heartbeat(master) ftp_settings = MAVFTPSettings( - [('debug', int, args.debug), - ('pkt_loss_tx', int, args.pkt_loss_tx), - ('pkt_loss_rx', int, args.pkt_loss_rx), - ('max_backlog', int, args.max_backlog), - ('burst_read_size', int, args.burst_read_size), - ('write_size', int, args.write_size), - ('write_qsize', int, args.write_qsize), - ('idle_detection_time', float, args.idle_detection_time), - ('read_retry_time', float, args.read_retry_time), - ('retry_time', float, args.retry_time)]) - - mav_ftp = MAVFTP(master, - target_system=master.target_system, - target_component=master.target_component, - settings=ftp_settings) + [ + ("debug", int, args.debug), + ("pkt_loss_tx", int, args.pkt_loss_tx), + ("pkt_loss_rx", int, args.pkt_loss_rx), + ("max_backlog", int, args.max_backlog), + ("burst_read_size", int, args.burst_read_size), + ("write_size", int, args.write_size), + ("write_qsize", int, args.write_qsize), + ("idle_detection_time", float, args.idle_detection_time), + ("read_retry_time", float, args.read_retry_time), + ("retry_time", float, args.retry_time), + ] + ) + + mav_ftp = MAVFTP( + master, target_system=master.target_system, target_component=master.target_component, settings=ftp_settings + ) cmd_ftp_args = [args.command] - if 'arg1' in args and args.arg1: + if "arg1" in args and args.arg1: cmd_ftp_args.append(args.arg1) - if 'arg2' in args and args.arg2: + if "arg2" in args and args.arg2: cmd_ftp_args.append(args.arg2) ret = mav_ftp.cmd_ftp(cmd_ftp_args) - if args.command in ['get', 'put', 'getparams']: + if args.command in ["get", "put", "getparams"]: ret = mav_ftp.process_ftp_reply(args.command, timeout=500) if isinstance(ret, str): @@ -1619,5 +1643,4 @@ def main(): master.close() - main() diff --git a/MethodicConfigurator/battery_cell_voltages.py b/MethodicConfigurator/battery_cell_voltages.py index 0cd4cb6..792a438 100644 --- a/MethodicConfigurator/battery_cell_voltages.py +++ b/MethodicConfigurator/battery_cell_voltages.py @@ -1,62 +1,62 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" from math import nan - battery_cell_voltages = { "LiIon": { "absolute_max": 4.1, "absolute_min": 2.5, "recommended_max": 4.1, "recommended_low": 3.1, - "recommended_crit": 2.8 + "recommended_crit": 2.8, }, "LiIonSS": { "absolute_max": 4.2, "absolute_min": 2.4, "recommended_max": 4.2, "recommended_low": 3.0, - "recommended_crit": 2.7 + "recommended_crit": 2.7, }, "LiIonSSHV": { "absolute_max": 4.45, "absolute_min": 2.4, "recommended_max": 4.45, "recommended_low": 3.0, - "recommended_crit": 2.7 + "recommended_crit": 2.7, }, "Lipo": { "absolute_max": 4.2, "absolute_min": 3.0, "recommended_max": 4.2, "recommended_low": 3.6, - "recommended_crit": 3.3 + "recommended_crit": 3.3, }, "LipoHV": { "absolute_max": 4.35, "absolute_min": 3.0, "recommended_max": 4.35, "recommended_low": 3.6, - "recommended_crit": 3.3 + "recommended_crit": 3.3, }, "LipoHVSS": { "absolute_max": 4.2, "absolute_min": 2.9, "recommended_max": 4.2, "recommended_low": 3.5, - "recommended_crit": 3.2 - } + "recommended_crit": 3.2, + }, # Add more chemistries as needed } + class BatteryCell: """ This class provides methods to work with battery cell voltages for different chemistries. @@ -64,38 +64,39 @@ class BatteryCell: It includes methods to get the list of chemistries, limit voltages based on chemistry type, and get recommended voltages for a given chemistry. """ + @staticmethod def chemistries() -> list: return list(battery_cell_voltages.keys()) @staticmethod def limit_max_voltage(chemistry: str) -> float: - max_abs_max = max(chemistry['absolute_max'] for chemistry in battery_cell_voltages.values()) + max_abs_max = max(chemistry["absolute_max"] for chemistry in battery_cell_voltages.values()) if chemistry not in battery_cell_voltages: return max_abs_max - return battery_cell_voltages[chemistry].get('absolute_max', max_abs_max) + return battery_cell_voltages[chemistry].get("absolute_max", max_abs_max) @staticmethod def limit_min_voltage(chemistry: str) -> float: - min_abs_min = min(chemistry['absolute_min'] for chemistry in battery_cell_voltages.values()) + min_abs_min = min(chemistry["absolute_min"] for chemistry in battery_cell_voltages.values()) if chemistry not in battery_cell_voltages: return min_abs_min - return battery_cell_voltages[chemistry].get('absolute_min', min_abs_min) + return battery_cell_voltages[chemistry].get("absolute_min", min_abs_min) @staticmethod def recommended_max_voltage(chemistry: str) -> float: if chemistry not in battery_cell_voltages: return nan - return battery_cell_voltages[chemistry].get('recommended_max', 4.2) + return battery_cell_voltages[chemistry].get("recommended_max", 4.2) @staticmethod def recommended_low_voltage(chemistry: str) -> float: if chemistry not in battery_cell_voltages: return nan - return battery_cell_voltages[chemistry].get('recommended_low', 3.6) + return battery_cell_voltages[chemistry].get("recommended_low", 3.6) @staticmethod def recommended_crit_voltage(chemistry: str) -> float: if chemistry not in battery_cell_voltages: return nan - return battery_cell_voltages[chemistry].get('recommended_crit', 3.3) + return battery_cell_voltages[chemistry].get("recommended_crit", 3.3) diff --git a/MethodicConfigurator/common_arguments.py b/MethodicConfigurator/common_arguments.py index 99de46f..2710bdb 100644 --- a/MethodicConfigurator/common_arguments.py +++ b/MethodicConfigurator/common_arguments.py @@ -1,31 +1,34 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" +from MethodicConfigurator import _ +from MethodicConfigurator.internationalization import LANGUAGE_CHOICES from MethodicConfigurator.version import VERSION -from MethodicConfigurator.internationalization import _, LANGUAGE_CHOICES - def add_common_arguments_and_parse(parser): - parser.add_argument('--loglevel', - type=str, - default='INFO', - choices=['DEBUG', 'INFO', 'WARNING', 'ERROR', 'CRITICAL'], - help=_('Logging level (default is %(default)s).')) - parser.add_argument('-v', '--version', - action='version', - version=f'%(prog)s {VERSION}', - help=_('Display version information and exit.')) - parser.add_argument('--language', - type=str, - default='en', - choices=LANGUAGE_CHOICES, - help=_('User interface language (default is %(default)s).')) + parser.add_argument( + "--loglevel", + type=str, + default="INFO", + choices=["DEBUG", "INFO", "WARNING", "ERROR", "CRITICAL"], + help=_("Logging level (default is %(default)s)."), + ) + parser.add_argument( + "-v", "--version", action="version", version=f"%(prog)s {VERSION}", help=_("Display version information and exit.") + ) + parser.add_argument( + "--language", + type=str, + default=LANGUAGE_CHOICES[0], + choices=LANGUAGE_CHOICES, + help=_("User interface language (default is %(default)s)."), + ) return parser.parse_args() diff --git a/MethodicConfigurator/extract_param_defaults.py b/MethodicConfigurator/extract_param_defaults.py index da86f00..d22b183 100755 --- a/MethodicConfigurator/extract_param_defaults.py +++ b/MethodicConfigurator/extract_param_defaults.py @@ -1,6 +1,6 @@ #!/usr/bin/python3 -''' +""" Extracts parameter values or parameter default values from an ArduPilot .bin log file. Supports Mission Planner, MAVProxy and QGCS file format output @@ -10,15 +10,16 @@ SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" import argparse import re from typing import Dict, Tuple + from pymavlink import mavutil NO_DEFAULT_VALUES_MESSAGE = "The .bin file contained no parameter default values. Update to a newer ArduPilot firmware version" -PARAM_NAME_REGEX = r'^[A-Z][A-Z_0-9]*$' +PARAM_NAME_REGEX = r"^[A-Z][A-Z_0-9]*$" PARAM_NAME_MAX_LEN = 16 MAVLINK_SYSID_MAX = 2**24 MAVLINK_COMPID_MAX = 2**8 @@ -35,35 +36,56 @@ def parse_arguments(args=None): Returns: Namespace object containing the parsed arguments. """ - parser = argparse.ArgumentParser(description='Extracts parameter default values from an ArduPilot .bin log file.') - parser.add_argument('-f', '--format', - choices=['missionplanner', 'mavproxy', 'qgcs'], - default='missionplanner', help='Output file format. Defaults to %(default)s.', - ) - parser.add_argument('-s', '--sort', - choices=['none', 'missionplanner', 'mavproxy', 'qgcs'], - default='', help='Sort the parameters in the file. Defaults to the same as the format.', - ) - parser.add_argument('-v', '--version', action='version', version='%(prog)s 1.1', - help='Display version information and exit.', - ) - parser.add_argument('-i', '--sysid', type=int, default=-1, - help='System ID for qgcs output format. Defaults to SYSID_THISMAV if defined else 1.', - ) - parser.add_argument('-c', '--compid', type=int, default=-1, - help='Component ID for qgcs output format. Defaults to 1.', - ) - parser.add_argument('-t', '--type', - choices=['defaults', 'values', 'non_default_values'], - default='defaults', help='Type of parameter values to extract. Defaults to %(default)s.', - ) - parser.add_argument('bin_file', help='The ArduPilot .bin log file to read') + parser = argparse.ArgumentParser(description="Extracts parameter default values from an ArduPilot .bin log file.") + parser.add_argument( + "-f", + "--format", + choices=["missionplanner", "mavproxy", "qgcs"], + default="missionplanner", + help="Output file format. Defaults to %(default)s.", + ) + parser.add_argument( + "-s", + "--sort", + choices=["none", "missionplanner", "mavproxy", "qgcs"], + default="", + help="Sort the parameters in the file. Defaults to the same as the format.", + ) + parser.add_argument( + "-v", + "--version", + action="version", + version="%(prog)s 1.1", + help="Display version information and exit.", + ) + parser.add_argument( + "-i", + "--sysid", + type=int, + default=-1, + help="System ID for qgcs output format. Defaults to SYSID_THISMAV if defined else 1.", + ) + parser.add_argument( + "-c", + "--compid", + type=int, + default=-1, + help="Component ID for qgcs output format. Defaults to 1.", + ) + parser.add_argument( + "-t", + "--type", + choices=["defaults", "values", "non_default_values"], + default="defaults", + help="Type of parameter values to extract. Defaults to %(default)s.", + ) + parser.add_argument("bin_file", help="The ArduPilot .bin log file to read") args, _ = parser.parse_known_args(args) - if args.sort == '': + if args.sort == "": args.sort = args.format - if args.format != 'qgcs': + if args.format != "qgcs": if args.sysid != -1: raise SystemExit("--sysid parameter is only relevant if --format is qgcs") if args.compid != -1: @@ -72,7 +94,7 @@ def parse_arguments(args=None): return args -def extract_parameter_values(logfile: str, param_type: str = 'defaults') -> Dict[str, float]: # pylint: disable=too-many-branches +def extract_parameter_values(logfile: str, param_type: str = "defaults") -> Dict[str, float]: # pylint: disable=too-many-branches """ Extracts the parameter values from an ArduPilot .bin log file. @@ -86,10 +108,10 @@ def extract_parameter_values(logfile: str, param_type: str = 'defaults') -> Dict try: mlog = mavutil.mavlink_connection(logfile) except Exception as e: - raise SystemExit(f"Error opening the {logfile} logfile: {str(e)}") from e + raise SystemExit(f"Error opening the {logfile} logfile: {e!s}") from e values = {} while True: - m = mlog.recv_match(type=['PARM']) + m = mlog.recv_match(type=["PARM"]) if m is None: if not values: raise SystemExit(NO_DEFAULT_VALUES_MESSAGE) @@ -102,14 +124,14 @@ def extract_parameter_values(logfile: str, param_type: str = 'defaults') -> Dict # parameter names are supposed to be unique if pname in values: continue - if param_type == 'defaults': - if hasattr(m, 'Default'): + if param_type == "defaults": + if hasattr(m, "Default"): values[pname] = m.Default - elif param_type == 'values': - if hasattr(m, 'Value'): + elif param_type == "values": + if hasattr(m, "Value"): values[pname] = m.Value - elif param_type == 'non_default_values': - if hasattr(m, 'Value') and hasattr(m, 'Default') and m.Value != m.Default: + elif param_type == "non_default_values": + if hasattr(m, "Value") and hasattr(m, "Default") and m.Value != m.Default: values[pname] = m.Value else: raise SystemExit(f"Invalid type {param_type}") @@ -143,7 +165,7 @@ def mavproxy_sort(item: str) -> str: return item -def sort_params(params: Dict[str, float], sort_type: str = 'none') -> Dict[str, float]: +def sort_params(params: Dict[str, float], sort_type: str = "none") -> Dict[str, float]: """ Sorts parameter names according to sort_type @@ -163,8 +185,12 @@ def sort_params(params: Dict[str, float], sort_type: str = 'none') -> Dict[str, return params -def output_params(params: Dict[str, float], format_type: str = 'missionplanner', # pylint: disable=too-many-branches - sysid: int = -1, compid: int = -1) -> None: +def output_params( # pylint: disable=too-many-branches + params: Dict[str, float], + format_type: str = "missionplanner", + sysid: int = -1, + compid: int = -1, +) -> None: """ Outputs parameters names and their values to the console @@ -177,19 +203,19 @@ def output_params(params: Dict[str, float], format_type: str = 'missionplanner', """ if format_type == "qgcs": if sysid == -1: - if 'SYSID_THISMAV' in params: - sysid = int(params['SYSID_THISMAV']) + if "SYSID_THISMAV" in params: + sysid = int(params["SYSID_THISMAV"]) else: sysid = 1 # if unspecified, default to 1 if compid == -1: compid = 1 # if unspecified, default to 1 if sysid < 0: raise SystemExit(f"Invalid system ID parameter {sysid} must not be negative") - if sysid > MAVLINK_SYSID_MAX-1: + if sysid > MAVLINK_SYSID_MAX - 1: raise SystemExit(f"Invalid system ID parameter {sysid} must be smaller than {MAVLINK_SYSID_MAX}") if compid < 0: raise SystemExit(f"Invalid component ID parameter {compid} must not be negative") - if compid > MAVLINK_COMPID_MAX-1: + if compid > MAVLINK_COMPID_MAX - 1: raise SystemExit(f"Invalid component ID parameter {compid} must be smaller than {MAVLINK_COMPID_MAX}") # see https://dev.qgroundcontrol.com/master/en/file_formats/parameters.html print(""" @@ -199,9 +225,9 @@ def output_params(params: Dict[str, float], format_type: str = 'missionplanner', for param_name, param_value in params.items(): if format_type == "missionplanner": try: - param_value = format(param_value, '.6f').rstrip('0').rstrip('.') + param_value = format(param_value, ".6f").rstrip("0").rstrip(".") except ValueError: - pass # preserve non-floating point strings, if present + pass # preserve non-floating point strings, if present print(f"{param_name},{param_value}") elif format_type == "mavproxy": print(f"{param_name:<15} {param_value:.6f}") diff --git a/MethodicConfigurator/frontend_tkinter_base.py b/MethodicConfigurator/frontend_tkinter_base.py index 17751bd..84e5964 100644 --- a/MethodicConfigurator/frontend_tkinter_base.py +++ b/MethodicConfigurator/frontend_tkinter_base.py @@ -1,58 +1,54 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" # https://wiki.tcl-lang.org/page/Changing+Widget+Colors import tkinter as tk -from tkinter import font as tkFont -from tkinter import messagebox -from tkinter import ttk -from tkinter import BooleanVar +from logging import error as logging_error # from logging import debug as logging_debug # from logging import info as logging_info from logging import warning as logging_warning -from logging import error as logging_error - from platform import system as platform_system +from tkinter import BooleanVar, messagebox, ttk +from tkinter import font as tkFont +from typing import Optional -from PIL import Image -from PIL import ImageTk +from PIL import Image, ImageTk from MethodicConfigurator.backend_filesystem import LocalFilesystem - from MethodicConfigurator.backend_filesystem_program_settings import ProgramSettings - -from MethodicConfigurator.internationalization import _ +from MethodicConfigurator import _ def show_error_message(title: str, message: str): root = tk.Tk() # Set the theme to 'alt' style = ttk.Style() - style.theme_use('alt') - root.withdraw() # Hide the main window + style.theme_use("alt") + root.withdraw() # Hide the main window messagebox.showerror(title, message) root.destroy() def show_no_param_files_error(_dirname: str): - error_message = _("No intermediate parameter files found in the selected '{_dirname}' vehicle directory.\n" \ - "Please select and step inside a vehicle directory containing valid ArduPilot intermediate parameter files.\n\n" \ - "Make sure to step inside the directory (double-click) and not just select it.") + error_message = _( + "No intermediate parameter files found in the selected '{_dirname}' vehicle directory.\n" + "Please select and step inside a vehicle directory containing valid ArduPilot intermediate parameter files.\n\n" + "Make sure to step inside the directory (double-click) and not just select it." + ) show_error_message(_("No Parameter Files Found"), error_message.format(**locals())) def show_no_connection_error(_error_string: str): - error_message = _("{_error_string}\n\nPlease connect a flight controller to the PC,\n" \ - "wait at least 7 seconds and retry.") + error_message = _("{_error_string}\n\nPlease connect a flight controller to the PC,\nwait at least 7 seconds and retry.") show_error_message(_("No Connection to the Flight Controller"), error_message.format(**locals())) @@ -71,7 +67,7 @@ def leave(_event): tooltip.wm_overrideredirect(True) tooltip_label = ttk.Label(tooltip, text=text, background="#ffffe0", relief="solid", borderwidth=1, justify=tk.LEFT) tooltip_label.pack() - tooltip.withdraw() # Initially hide the tooltip + tooltip.withdraw() # Initially hide the tooltip # Bind the and events to show and hide the tooltip widget.bind("", enter) @@ -80,9 +76,9 @@ def leave(_event): def update_combobox_width(combobox): # Calculate the maximum width needed for the content - max_width = max(len(value) for value in combobox['values']) + max_width = max(len(value) for value in combobox["values"]) # Set a minimum width for the combobox - min_width = 4 # Adjust this value as needed + min_width = 4 # Adjust this value as needed # Set the width of the combobox to the maximum width, but not less than the minimum width combobox.config(width=max(min_width, max_width)) @@ -101,20 +97,20 @@ class AutoResizeCombobox(ttk.Combobox): # pylint: disable=too-many-ancestors selected_element: The initially selected element in the Combobox. tooltip: A string representing the tooltip text to display when hovering over the widget. """ + def __init__(self, container, values, selected_element, tooltip, *args, **kwargs): super().__init__(container, *args, **kwargs) self.set_entries_tupple(values, selected_element, tooltip) def set_entries_tupple(self, values, selected_element, tooltip=None): - self['values'] = tuple(values) + self["values"] = tuple(values) if selected_element: if selected_element in values: self.set(selected_element) else: logging_error(_("param_file combobox selected string '%s' not in list %s"), selected_element, values) - else: - if values: - logging_warning(_("No param_file combobox element selected")) + elif values: + logging_warning(_("No param_file combobox element selected")) if values: update_combobox_width(self) if tooltip: @@ -129,11 +125,12 @@ class ScrollFrame(ttk.Frame): # pylint: disable=too-many-ancestors allowing for scrolling content within the frame. It's useful for creating scrollable areas within your application's GUI. """ + def __init__(self, parent): - super().__init__(parent) # create a frame (self) + super().__init__(parent) # create a frame (self) # place canvas on self, copy ttk.background to tk.background - self.canvas = tk.Canvas(self, borderwidth=0, background=ttk.Style(parent).lookup('TFrame', 'background')) + self.canvas = tk.Canvas(self, borderwidth=0, background=ttk.Style(parent).lookup("TFrame", "background")) # place a frame on the canvas, this frame will hold the child widgets self.view_port = ttk.Frame(self.canvas) @@ -143,11 +140,15 @@ def __init__(self, parent): # attach scrollbar action to scroll of canvas self.canvas.configure(yscrollcommand=self.vsb.set) - self.vsb.pack(side="right", fill="y") # pack scrollbar to right of self + self.vsb.pack(side="right", fill="y") # pack scrollbar to right of self # pack canvas to left of self and expand to fill self.canvas.pack(side="left", fill="both", expand=True) - self.canvas_window = self.canvas.create_window((4, 4), window=self.view_port, # add view port frame to canvas - anchor="nw", tags="self.view_port") + self.canvas_window = self.canvas.create_window( + (4, 4), + window=self.view_port, # add view port frame to canvas + anchor="nw", + tags="self.view_port", + ) # bind an event whenever the size of the view_port frame changes. self.view_port.bind("", self.on_frame_configure) @@ -155,15 +156,15 @@ def __init__(self, parent): self.canvas.bind("", self.on_canvas_configure) # bind wheel events when the cursor enters the control - self.view_port.bind('', self.on_enter) + self.view_port.bind("", self.on_enter) # unbind wheel events when the cursor leaves the control - self.view_port.bind('', self.on_leave) + self.view_port.bind("", self.on_leave) # perform an initial stretch on render, otherwise the scroll region has a tiny border until the first resize self.on_frame_configure(None) def on_frame_configure(self, _event): - '''Reset the scroll region to encompass the inner frame''' + """Reset the scroll region to encompass the inner frame""" # Whenever the size of the frame changes, alter the scroll region respectively. self.canvas.configure(scrollregion=self.canvas.bbox("all")) # Calculate the bounding box for the scroll region, starting from the second row @@ -174,35 +175,34 @@ def on_frame_configure(self, _event): # self.canvas.configure(scrollregion=bbox) def on_canvas_configure(self, event): - '''Reset the canvas window to encompass inner frame when required''' + """Reset the canvas window to encompass inner frame when required""" canvas_width = event.width # Whenever the size of the canvas changes alter the window region respectively. self.canvas.itemconfig(self.canvas_window, width=canvas_width) - def on_mouse_wheel(self, event): # cross platform scroll wheel event + def on_mouse_wheel(self, event): # cross platform scroll wheel event canvas_height = self.canvas.winfo_height() rows_height = self.canvas.bbox("all")[3] - if rows_height > canvas_height: # only scroll if the rows overflow the frame - if platform_system() == 'Windows': + if rows_height > canvas_height: # only scroll if the rows overflow the frame + if platform_system() == "Windows": self.canvas.yview_scroll(int(-1 * (event.delta / 120)), "units") - elif platform_system() == 'Darwin': + elif platform_system() == "Darwin": self.canvas.yview_scroll(int(-1 * event.delta), "units") - else: - if event.num == 4: - self.canvas.yview_scroll(-1, "units") - elif event.num == 5: - self.canvas.yview_scroll(1, "units") + elif event.num == 4: + self.canvas.yview_scroll(-1, "units") + elif event.num == 5: + self.canvas.yview_scroll(1, "units") - def on_enter(self, _event): # bind wheel events when the cursor enters the control - if platform_system() == 'Linux': + def on_enter(self, _event): # bind wheel events when the cursor enters the control + if platform_system() == "Linux": self.canvas.bind_all("", self.on_mouse_wheel) self.canvas.bind_all("", self.on_mouse_wheel) else: self.canvas.bind_all("", self.on_mouse_wheel) - def on_leave(self, _event): # unbind wheel events when the cursor leaves the control - if platform_system() == 'Linux': + def on_leave(self, _event): # unbind wheel events when the cursor leaves the control + if platform_system() == "Linux": self.canvas.unbind_all("") self.canvas.unbind_all("") else: @@ -216,7 +216,8 @@ class ProgressWindow: This class is responsible for creating a progress window that displays the progress of a task. It includes a progress bar and a label to display the progress message. """ - def __init__(self, parent, title, message: str="", width: int=300, height: int=80): # pylint: disable=too-many-arguments + + def __init__(self, parent, title, message: str = "", width: int = 300, height: int = 80): # pylint: disable=too-many-arguments self.parent = parent self.message = message self.progress_window = None @@ -233,7 +234,7 @@ def __create_progress_window(self, title: str, message, width, height): main_frame.pack(expand=True, fill=tk.BOTH) # Create a progress bar - self.progress_bar = ttk.Progressbar(main_frame, length=100, mode='determinate') + self.progress_bar = ttk.Progressbar(main_frame, length=100, mode="determinate") self.progress_bar.pack(side=tk.TOP, fill=tk.X, expand=False, padx=(5, 5), pady=(10, 10)) # Create a label to display the progress message @@ -249,7 +250,7 @@ def __create_progress_window(self, title: str, message, width, height): def update_progress_bar_300_pct(self, percent: int): self.message = _("Please be patient, {:.1f}% of {}% complete") - self.update_progress_bar(percent/3, max_value=100) + self.update_progress_bar(percent / 3, max_value=100) def update_progress_bar(self, current_value: int, max_value: int): """ @@ -266,8 +267,8 @@ def update_progress_bar(self, current_value: int, max_value: int): logging_error(msg.format(**locals())) return - self.progress_bar['value'] = current_value - self.progress_bar['maximum'] = max_value + self.progress_bar["value"] = current_value + self.progress_bar["maximum"] = max_value # Update the progress message self.progress_label.config(text=self.message.format(current_value, max_value)) @@ -305,6 +306,7 @@ class RichText(tk.Text): # pylint: disable=too-many-ancestors RichText in your UI definitions. Apply tags to text segments using the tag_add method and configure the appearance accordingly. """ + def __init__(self, *args, **kwargs): super().__init__(*args, **kwargs) @@ -317,7 +319,7 @@ def __init__(self, *args, **kwargs): bold_font.configure(weight="bold") italic_font.configure(slant="italic") - h1_font.configure(size=int(default_size*2), weight="bold") + h1_font.configure(size=int(default_size * 2), weight="bold") self.tag_configure("bold", font=bold_font) self.tag_configure("italic", font=italic_font) @@ -326,8 +328,8 @@ def __init__(self, *args, **kwargs): def get_widget_font(widget: tk.Widget) -> dict: style = ttk.Style() - widget_style = widget.cget('style') # Get the style used by the widget - font_name = style.lookup(widget_style, 'font') + widget_style = widget.cget("style") # Get the style used by the widget + font_name = style.lookup(widget_style, "font") return tkFont.nametofont(font_name).config() @@ -339,7 +341,8 @@ class BaseWindow: root window, applying a theme, and configuring the application icon. It also includes methods for creating a progress window and centering a window on its parent. """ - def __init__(self, root_tk: tk.Tk=None): + + def __init__(self, root_tk: Optional[tk.Tk] = None): if root_tk: self.root = tk.Toplevel(root_tk) else: @@ -347,7 +350,7 @@ def __init__(self, root_tk: tk.Tk=None): # Set the theme to 'alt' style = ttk.Style() - style.theme_use('alt') + style.theme_use("alt") style.configure("Bold.TLabel", font=("TkDefaultFont", 10, "bold")) self.main_frame = ttk.Frame(self.root) @@ -377,7 +380,7 @@ def center_window(window, parent): window.geometry(f"+{x}+{y}") @staticmethod - def put_image_in_label(parent: tk.Toplevel, filepath: str, image_height: int=40) -> ttk.Label: + def put_image_in_label(parent: tk.Toplevel, filepath: str, image_height: int = 40) -> ttk.Label: # Load the image and scale it down to image_height pixels in height image = Image.open(filepath) width, height = image.size @@ -390,17 +393,18 @@ def put_image_in_label(parent: tk.Toplevel, filepath: str, image_height: int=40) # Create a label with the resized image image_label = ttk.Label(parent, image=photo) - image_label.image = photo # Keep a reference to the image to prevent it from being garbage collected + image_label.image = photo # Keep a reference to the image to prevent it from being garbage collected return image_label -class UsagePopupWindow(): +class UsagePopupWindow: """ A class for creating and managing usage popup windows in the application. This class extends the BaseWindow class to provide functionality for displaying usage popups with instructions and options to show them again or dismiss. """ + def __init__(self): pass @@ -409,9 +413,14 @@ def should_display(ptype: str) -> bool: return ProgramSettings.display_usage_popup(ptype) @staticmethod - def display(parent: tk.Tk, usage_popup_window: BaseWindow, title: str, # pylint: disable=too-many-arguments - ptype: str, geometry: str, instructions_text: RichText): - + def display( # pylint: disable=too-many-arguments + parent: tk.Tk, + usage_popup_window: BaseWindow, + title: str, + ptype: str, + geometry: str, + instructions_text: RichText, + ): usage_popup_window.root.title(title) usage_popup_window.root.geometry(geometry) @@ -423,25 +432,32 @@ def display(parent: tk.Tk, usage_popup_window: BaseWindow, title: str, # pylint def update_show_again(): ProgramSettings.set_display_usage_popup(ptype, show_again_var.get()) - show_again_checkbox = ttk.Checkbutton(usage_popup_window.main_frame, text=_("Show this usage popup again"), - variable=show_again_var, command=update_show_again) + show_again_checkbox = ttk.Checkbutton( + usage_popup_window.main_frame, + text=_("Show this usage popup again"), + variable=show_again_var, + command=update_show_again, + ) show_again_checkbox.pack(pady=(10, 5)) - dismiss_button = ttk.Button(usage_popup_window.main_frame, text=_("Dismiss"), - command=lambda: UsagePopupWindow.close(usage_popup_window, parent)) + dismiss_button = ttk.Button( + usage_popup_window.main_frame, + text=_("Dismiss"), + command=lambda: UsagePopupWindow.close(usage_popup_window, parent), + ) dismiss_button.pack(pady=10) BaseWindow.center_window(usage_popup_window.root, parent) - usage_popup_window.root.attributes('-topmost', True) + usage_popup_window.root.attributes("-topmost", True) - if platform_system() == 'Windows': - parent.attributes('-disabled', True) # Disable parent window input + if platform_system() == "Windows": + parent.attributes("-disabled", True) # Disable parent window input usage_popup_window.root.protocol("WM_DELETE_WINDOW", lambda: UsagePopupWindow.close(usage_popup_window, parent)) @staticmethod def close(usage_popup_window, parent): usage_popup_window.root.destroy() - if platform_system() == 'Windows': - parent.attributes('-disabled', False) # Re-enable the parent window + if platform_system() == "Windows": + parent.attributes("-disabled", False) # Re-enable the parent window parent.focus_set() diff --git a/MethodicConfigurator/frontend_tkinter_component_editor.py b/MethodicConfigurator/frontend_tkinter_component_editor.py index 4ff6bab..c35ca35 100644 --- a/MethodicConfigurator/frontend_tkinter_component_editor.py +++ b/MethodicConfigurator/frontend_tkinter_component_editor.py @@ -1,40 +1,33 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" +import tkinter as tk from argparse import ArgumentParser - from logging import basicConfig as logging_basicConfig -from logging import getLevelName as logging_getLevelName + # from logging import debug as logging_debug -#from logging import info as logging_info +# from logging import info as logging_info from logging import error as logging_error - -import tkinter as tk -from tkinter import ttk +from logging import getLevelName as logging_getLevelName from math import log2 - -from MethodicConfigurator.common_arguments import add_common_arguments_and_parse +from tkinter import ttk from MethodicConfigurator.backend_filesystem import LocalFilesystem - from MethodicConfigurator.backend_filesystem_vehicle_components import VehicleComponents - from MethodicConfigurator.battery_cell_voltages import BatteryCell +from MethodicConfigurator.common_arguments import add_common_arguments_and_parse -from MethodicConfigurator.frontend_tkinter_component_editor_base import ComponentEditorWindowBase - -#from MethodicConfigurator.frontend_tkinter_base import show_tooltip +# from MethodicConfigurator.frontend_tkinter_base import show_tooltip from MethodicConfigurator.frontend_tkinter_base import show_error_message - -from MethodicConfigurator.internationalization import _ - +from MethodicConfigurator.frontend_tkinter_component_editor_base import ComponentEditorWindowBase +from MethodicConfigurator import _ from MethodicConfigurator.version import VERSION @@ -47,11 +40,17 @@ def argument_parser(): Returns: argparse.Namespace: An object containing the parsed arguments. """ - parser = ArgumentParser(description=_('A GUI for editing JSON files that contain vehicle component configurations. ' - 'Not to be used directly, but through the main ArduPilot methodic configurator script.')) + # pylint: disable=duplicate-code + parser = ArgumentParser( + description=_( + "A GUI for editing JSON files that contain vehicle component configurations. " + "Not to be used directly, but through the main ArduPilot methodic configurator script." + ) + ) parser = LocalFilesystem.add_argparse_arguments(parser) parser = ComponentEditorWindow.add_argparse_arguments(parser) return add_common_arguments_and_parse(parser) + # pylint: enable=duplicate-code class VoltageTooLowError(Exception): @@ -70,149 +69,151 @@ class VoltageTooHighError(Exception): rc_ports = ["RCin/SBUS"] serial_protocols_dict = { - '-1': {'type': serial_ports, 'protocol': 'None', 'component': None}, - '1': {'type': serial_ports, 'protocol': 'MAVLink1', 'component': 'Telemetry'}, - '2': {'type': serial_ports, 'protocol': 'MAVLink2', 'component': 'Telemetry'}, - '3': {'type': serial_ports, 'protocol': 'Frsky D', 'component': None}, - '4': {'type': serial_ports, 'protocol': 'Frsky SPort', 'component': None}, - '5': {'type': serial_ports, 'protocol': 'GPS', 'component': 'GNSS Receiver'}, - '7': {'type': serial_ports, 'protocol': 'Alexmos Gimbal Serial', 'component': None}, - '8': {'type': serial_ports, 'protocol': 'Gimbal', 'component': None}, - '9': {'type': serial_ports, 'protocol': 'Rangefinder', 'component': None}, - '10': {'type': serial_ports, 'protocol': 'FrSky SPort Passthrough (OpenTX)', 'component': None}, - '11': {'type': serial_ports, 'protocol': 'Lidar360', 'component': None}, - '13': {'type': serial_ports, 'protocol': 'Beacon', 'component': None}, - '14': {'type': serial_ports, 'protocol': 'Volz servo out', 'component': None}, - '15': {'type': serial_ports, 'protocol': 'SBus servo out', 'component': None}, - '16': {'type': serial_ports, 'protocol': 'ESC Telemetry', 'component': None}, - '17': {'type': serial_ports, 'protocol': 'Devo Telemetry', 'component': None}, - '18': {'type': serial_ports, 'protocol': 'OpticalFlow', 'component': None}, - '19': {'type': serial_ports, 'protocol': 'RobotisServo', 'component': None}, - '20': {'type': serial_ports, 'protocol': 'NMEA Output', 'component': None}, - '21': {'type': serial_ports, 'protocol': 'WindVane', 'component': None}, - '22': {'type': serial_ports, 'protocol': 'SLCAN', 'component': None}, - '23': {'type': serial_ports, 'protocol': 'RCIN', 'component': 'RC Receiver'}, - '24': {'type': serial_ports, 'protocol': 'EFI Serial', 'component': None}, - '25': {'type': serial_ports, 'protocol': 'LTM', 'component': None}, - '26': {'type': serial_ports, 'protocol': 'RunCam', 'component': None}, - '27': {'type': serial_ports, 'protocol': 'HottTelem', 'component': None}, - '28': {'type': serial_ports, 'protocol': 'Scripting', 'component': None}, - '29': {'type': serial_ports, 'protocol': 'Crossfire VTX', 'component': None}, - '30': {'type': serial_ports, 'protocol': 'Generator', 'component': None}, - '31': {'type': serial_ports, 'protocol': 'Winch', 'component': None}, - '32': {'type': serial_ports, 'protocol': 'MSP', 'component': None}, - '33': {'type': serial_ports, 'protocol': 'DJI FPV', 'component': None}, - '34': {'type': serial_ports, 'protocol': 'AirSpeed', 'component': None}, - '35': {'type': serial_ports, 'protocol': 'ADSB', 'component': None}, - '36': {'type': serial_ports, 'protocol': 'AHRS', 'component': None}, - '37': {'type': serial_ports, 'protocol': 'SmartAudio', 'component': None}, - '38': {'type': serial_ports, 'protocol': 'FETtecOneWire', 'component': 'ESC'}, - '39': {'type': serial_ports, 'protocol': 'Torqeedo', 'component': 'ESC'}, - '40': {'type': serial_ports, 'protocol': 'AIS', 'component': None}, - '41': {'type': serial_ports, 'protocol': 'CoDevESC', 'component': 'ESC'}, - '42': {'type': serial_ports, 'protocol': 'DisplayPort', 'component': None}, - '43': {'type': serial_ports, 'protocol': 'MAVLink High Latency', 'component': 'Telemetry'}, - '44': {'type': serial_ports, 'protocol': 'IRC Tramp', 'component': None}, - '45': {'type': serial_ports, 'protocol': 'DDS XRCE', 'component': None}, - '46': {'type': serial_ports, 'protocol': 'IMUDATA', 'component': None}, + "-1": {"type": serial_ports, "protocol": "None", "component": None}, + "1": {"type": serial_ports, "protocol": "MAVLink1", "component": "Telemetry"}, + "2": {"type": serial_ports, "protocol": "MAVLink2", "component": "Telemetry"}, + "3": {"type": serial_ports, "protocol": "Frsky D", "component": None}, + "4": {"type": serial_ports, "protocol": "Frsky SPort", "component": None}, + "5": {"type": serial_ports, "protocol": "GPS", "component": "GNSS Receiver"}, + "7": {"type": serial_ports, "protocol": "Alexmos Gimbal Serial", "component": None}, + "8": {"type": serial_ports, "protocol": "Gimbal", "component": None}, + "9": {"type": serial_ports, "protocol": "Rangefinder", "component": None}, + "10": {"type": serial_ports, "protocol": "FrSky SPort Passthrough (OpenTX)", "component": None}, + "11": {"type": serial_ports, "protocol": "Lidar360", "component": None}, + "13": {"type": serial_ports, "protocol": "Beacon", "component": None}, + "14": {"type": serial_ports, "protocol": "Volz servo out", "component": None}, + "15": {"type": serial_ports, "protocol": "SBus servo out", "component": None}, + "16": {"type": serial_ports, "protocol": "ESC Telemetry", "component": None}, + "17": {"type": serial_ports, "protocol": "Devo Telemetry", "component": None}, + "18": {"type": serial_ports, "protocol": "OpticalFlow", "component": None}, + "19": {"type": serial_ports, "protocol": "RobotisServo", "component": None}, + "20": {"type": serial_ports, "protocol": "NMEA Output", "component": None}, + "21": {"type": serial_ports, "protocol": "WindVane", "component": None}, + "22": {"type": serial_ports, "protocol": "SLCAN", "component": None}, + "23": {"type": serial_ports, "protocol": "RCIN", "component": "RC Receiver"}, + "24": {"type": serial_ports, "protocol": "EFI Serial", "component": None}, + "25": {"type": serial_ports, "protocol": "LTM", "component": None}, + "26": {"type": serial_ports, "protocol": "RunCam", "component": None}, + "27": {"type": serial_ports, "protocol": "HottTelem", "component": None}, + "28": {"type": serial_ports, "protocol": "Scripting", "component": None}, + "29": {"type": serial_ports, "protocol": "Crossfire VTX", "component": None}, + "30": {"type": serial_ports, "protocol": "Generator", "component": None}, + "31": {"type": serial_ports, "protocol": "Winch", "component": None}, + "32": {"type": serial_ports, "protocol": "MSP", "component": None}, + "33": {"type": serial_ports, "protocol": "DJI FPV", "component": None}, + "34": {"type": serial_ports, "protocol": "AirSpeed", "component": None}, + "35": {"type": serial_ports, "protocol": "ADSB", "component": None}, + "36": {"type": serial_ports, "protocol": "AHRS", "component": None}, + "37": {"type": serial_ports, "protocol": "SmartAudio", "component": None}, + "38": {"type": serial_ports, "protocol": "FETtecOneWire", "component": "ESC"}, + "39": {"type": serial_ports, "protocol": "Torqeedo", "component": "ESC"}, + "40": {"type": serial_ports, "protocol": "AIS", "component": None}, + "41": {"type": serial_ports, "protocol": "CoDevESC", "component": "ESC"}, + "42": {"type": serial_ports, "protocol": "DisplayPort", "component": None}, + "43": {"type": serial_ports, "protocol": "MAVLink High Latency", "component": "Telemetry"}, + "44": {"type": serial_ports, "protocol": "IRC Tramp", "component": None}, + "45": {"type": serial_ports, "protocol": "DDS XRCE", "component": None}, + "46": {"type": serial_ports, "protocol": "IMUDATA", "component": None}, } batt_monitor_connection = { - '0': {'type': 'None', 'protocol': 'Disabled'}, - '3': {'type': 'Analog', 'protocol': 'Analog Voltage Only'}, - '4': {'type': 'Analog', 'protocol': 'Analog Voltage and Current'}, - '5': {'type': 'i2c', 'protocol': 'Solo'}, - '6': {'type': 'i2c', 'protocol': 'Bebop'}, - '7': {'type': 'i2c', 'protocol': 'SMBus-Generic'}, - '8': {'type': 'can', 'protocol': 'DroneCAN-BatteryInfo'}, - '9': {'type': 'None', 'protocol': 'ESC'}, - '10': {'type': 'None', 'protocol': 'Sum Of Selected Monitors'}, - '11': {'type': 'i2c', 'protocol': 'FuelFlow'}, - '12': {'type': 'pwm', 'protocol': 'FuelLevelPWM'}, - '13': {'type': 'i2c', 'protocol': 'SMBUS-SUI3'}, - '14': {'type': 'i2c', 'protocol': 'SMBUS-SUI6'}, - '15': {'type': 'i2c', 'protocol': 'NeoDesign'}, - '16': {'type': 'i2c', 'protocol': 'SMBus-Maxell'}, - '17': {'type': 'i2c', 'protocol': 'Generator-Elec'}, - '18': {'type': 'i2c', 'protocol': 'Generator-Fuel'}, - '19': {'type': 'i2c', 'protocol': 'Rotoye'}, - '20': {'type': 'i2c', 'protocol': 'MPPT'}, - '21': {'type': 'i2c', 'protocol': 'INA2XX'}, - '22': {'type': 'i2c', 'protocol': 'LTC2946'}, - '23': {'type': 'None', 'protocol': 'Torqeedo'}, - '24': {'type': 'Analog', 'protocol': 'FuelLevelAnalog'}, - '25': {'type': 'Analog', 'protocol': 'Synthetic Current and Analog Voltage'}, - '26': {'type': 'spi', 'protocol': 'INA239_SPI'}, - '27': {'type': 'i2c', 'protocol': 'EFI'}, - '28': {'type': 'i2c', 'protocol': 'AD7091R5'}, - '29': {'type': 'None', 'protocol': 'Scripting'}, + "0": {"type": "None", "protocol": "Disabled"}, + "3": {"type": "Analog", "protocol": "Analog Voltage Only"}, + "4": {"type": "Analog", "protocol": "Analog Voltage and Current"}, + "5": {"type": "i2c", "protocol": "Solo"}, + "6": {"type": "i2c", "protocol": "Bebop"}, + "7": {"type": "i2c", "protocol": "SMBus-Generic"}, + "8": {"type": "can", "protocol": "DroneCAN-BatteryInfo"}, + "9": {"type": "None", "protocol": "ESC"}, + "10": {"type": "None", "protocol": "Sum Of Selected Monitors"}, + "11": {"type": "i2c", "protocol": "FuelFlow"}, + "12": {"type": "pwm", "protocol": "FuelLevelPWM"}, + "13": {"type": "i2c", "protocol": "SMBUS-SUI3"}, + "14": {"type": "i2c", "protocol": "SMBUS-SUI6"}, + "15": {"type": "i2c", "protocol": "NeoDesign"}, + "16": {"type": "i2c", "protocol": "SMBus-Maxell"}, + "17": {"type": "i2c", "protocol": "Generator-Elec"}, + "18": {"type": "i2c", "protocol": "Generator-Fuel"}, + "19": {"type": "i2c", "protocol": "Rotoye"}, + "20": {"type": "i2c", "protocol": "MPPT"}, + "21": {"type": "i2c", "protocol": "INA2XX"}, + "22": {"type": "i2c", "protocol": "LTC2946"}, + "23": {"type": "None", "protocol": "Torqeedo"}, + "24": {"type": "Analog", "protocol": "FuelLevelAnalog"}, + "25": {"type": "Analog", "protocol": "Synthetic Current and Analog Voltage"}, + "26": {"type": "spi", "protocol": "INA239_SPI"}, + "27": {"type": "i2c", "protocol": "EFI"}, + "28": {"type": "i2c", "protocol": "AD7091R5"}, + "29": {"type": "None", "protocol": "Scripting"}, } gnss_receiver_connection = { - '0': {'type': None, 'protocol': 'None'}, - '1': {'type': 'serial', 'protocol': 'AUTO'}, - '2': {'type': 'serial', 'protocol': 'uBlox'}, - '5': {'type': 'serial', 'protocol': 'NMEA'}, - '6': {'type': 'serial', 'protocol': 'SiRF'}, - '7': {'type': 'serial', 'protocol': 'HIL'}, - '8': {'type': 'serial', 'protocol': 'SwiftNav'}, - '9': {'type': 'can', 'protocol': 'DroneCAN'}, - '10': {'type': 'serial', 'protocol': 'SBF'}, - '11': {'type': 'serial', 'protocol': 'GSOF'}, - '13': {'type': 'serial', 'protocol': 'ERB'}, - '14': {'type': 'serial', 'protocol': 'MAV'}, - '15': {'type': 'serial', 'protocol': 'NOVA'}, - '16': {'type': 'serial', 'protocol': 'HemisphereNMEA'}, - '17': {'type': 'serial', 'protocol': 'uBlox-MovingBaseline-Base'}, - '18': {'type': 'serial', 'protocol': 'uBlox-MovingBaseline-Rover'}, - '19': {'type': 'serial', 'protocol': 'MSP'}, - '20': {'type': 'serial', 'protocol': 'AllyStar'}, - '21': {'type': 'serial', 'protocol': 'ExternalAHRS'}, - '22': {'type': 'can', 'protocol': 'DroneCAN-MovingBaseline-Base'}, - '23': {'type': 'can', 'protocol': 'DroneCAN-MovingBaseline-Rover'}, - '24': {'type': 'serial', 'protocol': 'UnicoreNMEA'}, - '25': {'type': 'serial', 'protocol': 'UnicoreMovingBaselineNMEA'}, - '26': {'type': 'serial', 'protocol': 'SBF-DualAntenna'}, + "0": {"type": None, "protocol": "None"}, + "1": {"type": "serial", "protocol": "AUTO"}, + "2": {"type": "serial", "protocol": "uBlox"}, + "5": {"type": "serial", "protocol": "NMEA"}, + "6": {"type": "serial", "protocol": "SiRF"}, + "7": {"type": "serial", "protocol": "HIL"}, + "8": {"type": "serial", "protocol": "SwiftNav"}, + "9": {"type": "can", "protocol": "DroneCAN"}, + "10": {"type": "serial", "protocol": "SBF"}, + "11": {"type": "serial", "protocol": "GSOF"}, + "13": {"type": "serial", "protocol": "ERB"}, + "14": {"type": "serial", "protocol": "MAV"}, + "15": {"type": "serial", "protocol": "NOVA"}, + "16": {"type": "serial", "protocol": "HemisphereNMEA"}, + "17": {"type": "serial", "protocol": "uBlox-MovingBaseline-Base"}, + "18": {"type": "serial", "protocol": "uBlox-MovingBaseline-Rover"}, + "19": {"type": "serial", "protocol": "MSP"}, + "20": {"type": "serial", "protocol": "AllyStar"}, + "21": {"type": "serial", "protocol": "ExternalAHRS"}, + "22": {"type": "can", "protocol": "DroneCAN-MovingBaseline-Base"}, + "23": {"type": "can", "protocol": "DroneCAN-MovingBaseline-Rover"}, + "24": {"type": "serial", "protocol": "UnicoreNMEA"}, + "25": {"type": "serial", "protocol": "UnicoreMovingBaselineNMEA"}, + "26": {"type": "serial", "protocol": "SBF-DualAntenna"}, } mot_pwm_type_dict = { - '0': {'type': 'Main Out', 'protocol': 'Normal', 'is_dshot': False}, - '1': {'type': 'Main Out', 'protocol': 'OneShot', 'is_dshot': True}, - '2': {'type': 'Main Out', 'protocol': 'OneShot125', 'is_dshot': True}, - '3': {'type': 'Main Out', 'protocol': 'Brushed', 'is_dshot': False}, - '4': {'type': 'Main Out', 'protocol': 'DShot150', 'is_dshot': True}, - '5': {'type': 'Main Out', 'protocol': 'DShot300', 'is_dshot': True}, - '6': {'type': 'Main Out', 'protocol': 'DShot600', 'is_dshot': True}, - '7': {'type': 'Main Out', 'protocol': 'DShot1200', 'is_dshot': True}, - '8': {'type': 'Main Out', 'protocol': 'PWMRange', 'is_dshot': False}, + "0": {"type": "Main Out", "protocol": "Normal", "is_dshot": False}, + "1": {"type": "Main Out", "protocol": "OneShot", "is_dshot": True}, + "2": {"type": "Main Out", "protocol": "OneShot125", "is_dshot": True}, + "3": {"type": "Main Out", "protocol": "Brushed", "is_dshot": False}, + "4": {"type": "Main Out", "protocol": "DShot150", "is_dshot": True}, + "5": {"type": "Main Out", "protocol": "DShot300", "is_dshot": True}, + "6": {"type": "Main Out", "protocol": "DShot600", "is_dshot": True}, + "7": {"type": "Main Out", "protocol": "DShot1200", "is_dshot": True}, + "8": {"type": "Main Out", "protocol": "PWMRange", "is_dshot": False}, } rc_protocols_dict = { - '0': {'type': 'RCin/SBUS', 'protocol': 'All'}, - '1': {'type': 'RCin/SBUS', 'protocol': 'PPM'}, - '2': {'type': 'RCin/SBUS', 'protocol': 'IBUS'}, - '3': {'type': 'RCin/SBUS', 'protocol': 'SBUS'}, - '4': {'type': 'RCin/SBUS', 'protocol': 'SBUS_NI'}, - '5': {'type': 'RCin/SBUS', 'protocol': 'DSM'}, - '6': {'type': 'RCin/SBUS', 'protocol': 'SUMD'}, - '7': {'type': 'RCin/SBUS', 'protocol': 'SRXL'}, - '8': {'type': 'RCin/SBUS', 'protocol': 'SRXL2'}, - '9': {'type': 'RCin/SBUS', 'protocol': 'CRSF'}, - '10': {'type': 'RCin/SBUS', 'protocol': 'ST24'}, - '11': {'type': 'RCin/SBUS', 'protocol': 'FPORT'}, - '12': {'type': 'RCin/SBUS', 'protocol': 'FPORT2'}, - '13': {'type': 'RCin/SBUS', 'protocol': 'FastSBUS'}, - '14': {'type': 'can', 'protocol': 'DroneCAN'}, - '15': {'type': 'RCin/SBUS', 'protocol': 'Ghost'}, + "0": {"type": "RCin/SBUS", "protocol": "All"}, + "1": {"type": "RCin/SBUS", "protocol": "PPM"}, + "2": {"type": "RCin/SBUS", "protocol": "IBUS"}, + "3": {"type": "RCin/SBUS", "protocol": "SBUS"}, + "4": {"type": "RCin/SBUS", "protocol": "SBUS_NI"}, + "5": {"type": "RCin/SBUS", "protocol": "DSM"}, + "6": {"type": "RCin/SBUS", "protocol": "SUMD"}, + "7": {"type": "RCin/SBUS", "protocol": "SRXL"}, + "8": {"type": "RCin/SBUS", "protocol": "SRXL2"}, + "9": {"type": "RCin/SBUS", "protocol": "CRSF"}, + "10": {"type": "RCin/SBUS", "protocol": "ST24"}, + "11": {"type": "RCin/SBUS", "protocol": "FPORT"}, + "12": {"type": "RCin/SBUS", "protocol": "FPORT2"}, + "13": {"type": "RCin/SBUS", "protocol": "FastSBUS"}, + "14": {"type": "can", "protocol": "DroneCAN"}, + "15": {"type": "RCin/SBUS", "protocol": "Ghost"}, } + class ComponentEditorWindow(ComponentEditorWindowBase): """ This class validates the user input and handles user interactions for editing component configurations in the ArduPilot Methodic Configurator. """ - def __init__(self, version, local_filesystem: LocalFilesystem=None): + + def __init__(self, version, local_filesystem: LocalFilesystem = None): self.serial_ports = ["SERIAL1", "SERIAL2", "SERIAL3", "SERIAL4", "SERIAL5", "SERIAL6", "SERIAL7", "SERIAL8"] self.can_ports = ["CAN1", "CAN2"] self.i2c_ports = ["I2C1", "I2C2", "I2C3", "I2C4"] @@ -221,48 +222,48 @@ def __init__(self, version, local_filesystem: LocalFilesystem=None): def update_json_data(self): super().update_json_data() # To update old JSON files that do not have these new fields - if 'Components' not in self.data: - self.data['Components'] = {} - if 'Battery' not in self.data['Components']: - self.data['Components']['Battery'] = {} - if 'Specifications' not in self.data['Components']['Battery']: - self.data['Components']['Battery']['Specifications'] = {} - if 'Chemistry' not in self.data['Components']['Battery']['Specifications']: - self.data['Components']['Battery']['Specifications']['Chemistry'] = "Lipo" - if 'Capacity mAh' not in self.data['Components']['Battery']['Specifications']: - self.data['Components']['Battery']['Specifications']['Capacity mAh'] = 0 + if "Components" not in self.data: + self.data["Components"] = {} + if "Battery" not in self.data["Components"]: + self.data["Components"]["Battery"] = {} + if "Specifications" not in self.data["Components"]["Battery"]: + self.data["Components"]["Battery"]["Specifications"] = {} + if "Chemistry" not in self.data["Components"]["Battery"]["Specifications"]: + self.data["Components"]["Battery"]["Specifications"]["Chemistry"] = "Lipo" + if "Capacity mAh" not in self.data["Components"]["Battery"]["Specifications"]: + self.data["Components"]["Battery"]["Specifications"]["Capacity mAh"] = 0 # To update old JSON files that do not have these new fields - if 'Frame' not in self.data['Components']: - self.data['Components']['Frame'] = {} - if 'Specifications' not in self.data['Components']['Frame']: - self.data['Components']['Frame']['Specifications'] = {} - if 'TOW min Kg' not in self.data['Components']['Frame']['Specifications']: - self.data['Components']['Frame']['Specifications']['TOW min Kg'] = 1 - if 'TOW max Kg' not in self.data['Components']['Frame']['Specifications']: - self.data['Components']['Frame']['Specifications']['TOW max Kg'] = 1 + if "Frame" not in self.data["Components"]: + self.data["Components"]["Frame"] = {} + if "Specifications" not in self.data["Components"]["Frame"]: + self.data["Components"]["Frame"]["Specifications"] = {} + if "TOW min Kg" not in self.data["Components"]["Frame"]["Specifications"]: + self.data["Components"]["Frame"]["Specifications"]["TOW min Kg"] = 1 + if "TOW max Kg" not in self.data["Components"]["Frame"]["Specifications"]: + self.data["Components"]["Frame"]["Specifications"]["TOW max Kg"] = 1 # Older versions used receiver instead of Receiver, rename it for consistency with other fields - if 'GNSS receiver' in self.data['Components']: - self.data['Components']['GNSS Receiver'] = self.data['Components'].pop('GNSS receiver') + if "GNSS receiver" in self.data["Components"]: + self.data["Components"]["GNSS Receiver"] = self.data["Components"].pop("GNSS receiver") - self.data['Program version'] = VERSION + self.data["Program version"] = VERSION def set_vehicle_type_and_version(self, vehicle_type: str, version: str): - self._set_component_value_and_update_ui(('Flight Controller', 'Firmware', 'Type'), vehicle_type) + self._set_component_value_and_update_ui(("Flight Controller", "Firmware", "Type"), vehicle_type) if version: - self._set_component_value_and_update_ui(('Flight Controller', 'Firmware', 'Version'), version) + self._set_component_value_and_update_ui(("Flight Controller", "Firmware", "Version"), version) def set_fc_manufacturer(self, manufacturer: str): - if manufacturer and manufacturer!= "Unknown" and manufacturer!= "ArduPilot": - self._set_component_value_and_update_ui(('Flight Controller', 'Product', 'Manufacturer'), manufacturer) + if manufacturer and manufacturer != "Unknown" and manufacturer != "ArduPilot": + self._set_component_value_and_update_ui(("Flight Controller", "Product", "Manufacturer"), manufacturer) def set_fc_model(self, model: str): - if model and model!= "Unknown" and model!= "MAVLink": - self._set_component_value_and_update_ui(('Flight Controller', 'Product', 'Model'), model) + if model and model != "Unknown" and model != "MAVLink": + self._set_component_value_and_update_ui(("Flight Controller", "Product", "Model"), model) def set_vehicle_configuration_template(self, configuration_template: str): - self.data['Configuration template'] = configuration_template + self.data["Configuration template"] = configuration_template @staticmethod def reverse_key_search(doc: dict, param_name: str, values: list, fallbacks: list) -> list: @@ -275,22 +276,22 @@ def reverse_key_search(doc: dict, param_name: str, values: list, fallbacks: list return fallbacks def __assert_dict_is_uptodate(self, doc: dict, dict_to_check: dict, doc_key: str, doc_dict: str): - """ Asserts that the given dictionary is up-to-date with the apm.pdef.xml documentation metadata. """ + """Asserts that the given dictionary is up-to-date with the apm.pdef.xml documentation metadata.""" if doc and doc_key in doc and doc[doc_key] and doc_dict in doc[doc_key]: for key, doc_protocol in doc[doc_key][doc_dict].items(): if key in dict_to_check: - code_protocol = dict_to_check[key].get('protocol', None) + code_protocol = dict_to_check[key].get("protocol", None) if code_protocol != doc_protocol: logging_error(_("Protocol %s does not match %s in %s metadata"), code_protocol, doc_protocol, doc_key) else: logging_error(_("Protocol %s not found in %s metadata"), doc_protocol, doc_key) def set_values_from_fc_parameters(self, fc_parameters: dict, doc: dict): - self.__assert_dict_is_uptodate(doc, serial_protocols_dict, 'SERIAL1_PROTOCOL', 'values') - self.__assert_dict_is_uptodate(doc, batt_monitor_connection, 'BATT_MONITOR', 'values') - self.__assert_dict_is_uptodate(doc, gnss_receiver_connection, 'GPS_TYPE', 'values') - self.__assert_dict_is_uptodate(doc, mot_pwm_type_dict, 'MOT_PWM_TYPE', 'values') - self.__assert_dict_is_uptodate(doc, rc_protocols_dict, 'RC_PROTOCOLS', 'Bitmask') + self.__assert_dict_is_uptodate(doc, serial_protocols_dict, "SERIAL1_PROTOCOL", "values") + self.__assert_dict_is_uptodate(doc, batt_monitor_connection, "BATT_MONITOR", "values") + self.__assert_dict_is_uptodate(doc, gnss_receiver_connection, "GPS_TYPE", "values") + self.__assert_dict_is_uptodate(doc, mot_pwm_type_dict, "MOT_PWM_TYPE", "values") + self.__assert_dict_is_uptodate(doc, rc_protocols_dict, "RC_PROTOCOLS", "Bitmask") self.__set_gnss_type_and_protocol_from_fc_parameters(fc_parameters) esc_is_serial_controlled = self.__set_serial_type_and_protocol_from_fc_parameters(fc_parameters) @@ -300,49 +301,60 @@ def set_values_from_fc_parameters(self, fc_parameters: dict, doc: dict): self.__set_motor_poles_from_fc_parameters(fc_parameters) def __set_gnss_type_and_protocol_from_fc_parameters(self, fc_parameters: dict): - gps1_type = fc_parameters['GPS_TYPE'] if "GPS_TYPE" in fc_parameters else 0 + gps1_type = fc_parameters["GPS_TYPE"] if "GPS_TYPE" in fc_parameters else 0 try: gps1_type = int(gps1_type) except ValueError: logging_error(_("Invalid non-integer value for GPS_TYPE %f"), gps1_type) gps1_type = 0 if str(gps1_type) in gnss_receiver_connection: - gps1_connection_type = gnss_receiver_connection[str(gps1_type)].get('type') - gps1_connection_protocol = gnss_receiver_connection[str(gps1_type)].get('protocol') + gps1_connection_type = gnss_receiver_connection[str(gps1_type)].get("type") + gps1_connection_protocol = gnss_receiver_connection[str(gps1_type)].get("protocol") if gps1_connection_type is None: - self.data['Components']['GNSS Receiver']['FC Connection']['Type'] = "None" - self.data['Components']['GNSS Receiver']['FC Connection']['Protocol'] = "None" - elif gps1_connection_type == 'serial': + self.data["Components"]["GNSS Receiver"]["FC Connection"]["Type"] = "None" + self.data["Components"]["GNSS Receiver"]["FC Connection"]["Protocol"] = "None" + elif gps1_connection_type == "serial": # GNSS connection type will be detected later in set_protocol_and_connection_from_fc_parameters() - self.data['Components']['GNSS Receiver']['FC Connection']['Protocol'] = gps1_connection_protocol - elif gps1_connection_type == 'can': - if 'CAN_D1_PROTOCOL' in fc_parameters and fc_parameters['CAN_D1_PROTOCOL'] == 1 and \ - 'CAN_P1_DRIVER' in fc_parameters and fc_parameters['CAN_P1_DRIVER'] == 1: - self.data['Components']['GNSS Receiver']['FC Connection']['Type'] = "CAN1" - elif 'CAN_D2_PROTOCOL' in fc_parameters and fc_parameters['CAN_D2_PROTOCOL'] == 1 and \ - 'CAN_P2_DRIVER' in fc_parameters and fc_parameters['CAN_P2_DRIVER'] == 2: - self.data['Components']['GNSS Receiver']['FC Connection']['Type'] = "CAN2" + self.data["Components"]["GNSS Receiver"]["FC Connection"]["Protocol"] = gps1_connection_protocol + elif gps1_connection_type == "can": + if ( + "CAN_D1_PROTOCOL" in fc_parameters + and fc_parameters["CAN_D1_PROTOCOL"] == 1 + and "CAN_P1_DRIVER" in fc_parameters + and fc_parameters["CAN_P1_DRIVER"] == 1 + ): + self.data["Components"]["GNSS Receiver"]["FC Connection"]["Type"] = "CAN1" + elif ( + "CAN_D2_PROTOCOL" in fc_parameters + and fc_parameters["CAN_D2_PROTOCOL"] == 1 + and "CAN_P2_DRIVER" in fc_parameters + and fc_parameters["CAN_P2_DRIVER"] == 2 + ): + self.data["Components"]["GNSS Receiver"]["FC Connection"]["Type"] = "CAN2" else: - logging_error(_("Invalid CAN_Dx_PROTOCOL %s and CAN_Px_DRIVER %s for GNSS Receiver"), - fc_parameters.get('CAN_D1_PROTOCOL'), fc_parameters.get('CAN_P1_DRIVER')) - self.data['Components']['GNSS Receiver']['FC Connection']['Type'] = "None" - self.data['Components']['GNSS Receiver']['FC Connection']['Protocol'] = gps1_connection_protocol + logging_error( + _("Invalid CAN_Dx_PROTOCOL %s and CAN_Px_DRIVER %s for GNSS Receiver"), + fc_parameters.get("CAN_D1_PROTOCOL"), + fc_parameters.get("CAN_P1_DRIVER"), + ) + self.data["Components"]["GNSS Receiver"]["FC Connection"]["Type"] = "None" + self.data["Components"]["GNSS Receiver"]["FC Connection"]["Protocol"] = gps1_connection_protocol else: logging_error("Invalid GNSS connection type %s", gps1_connection_type) - self.data['Components']['GNSS Receiver']['FC Connection']['Type'] = "None" + self.data["Components"]["GNSS Receiver"]["FC Connection"]["Type"] = "None" else: logging_error("GPS_TYPE %u not in gnss_receiver_connection", gps1_type) - self.data['Components']['GNSS Receiver']['FC Connection']['Type'] = "None" + self.data["Components"]["GNSS Receiver"]["FC Connection"]["Type"] = "None" def __set_serial_type_and_protocol_from_fc_parameters(self, fc_parameters: dict): - if 'RC_PROTOCOLS' in fc_parameters: - rc_protocols_nr = int(fc_parameters['RC_PROTOCOLS']) + if "RC_PROTOCOLS" in fc_parameters: + rc_protocols_nr = int(fc_parameters["RC_PROTOCOLS"]) # check if rc_protocols_nr is a power of two (only one bit set) if rc_protocols_nr & (rc_protocols_nr - 1) == 0: # rc_bit is the number of the bit that is set rc_bit = str(int(log2(rc_protocols_nr))) - protocol = rc_protocols_dict[rc_bit].get('protocol') - self.data['Components']['RC Receiver']['FC Connection']['Protocol'] = protocol + protocol = rc_protocols_dict[rc_bit].get("protocol") + self.data["Components"]["RC Receiver"]["FC Connection"]["Protocol"] = protocol rc = 1 telem = 1 @@ -358,91 +370,92 @@ def __set_serial_type_and_protocol_from_fc_parameters(self, fc_parameters: dict) msg = _("Invalid non-integer value for {serial}_PROTOCOL {serial_protocol_nr}") logging_error(msg.format(**locals())) serial_protocol_nr = 0 - component = serial_protocols_dict[str(serial_protocol_nr)].get('component') - protocol = serial_protocols_dict[str(serial_protocol_nr)].get('protocol') + component = serial_protocols_dict[str(serial_protocol_nr)].get("component") + protocol = serial_protocols_dict[str(serial_protocol_nr)].get("protocol") if component is None: continue - if component == 'RC Receiver' and rc == 1: - self.data['Components'][component]['FC Connection']['Type'] = serial # only one RC supported + if component == "RC Receiver" and rc == 1: + self.data["Components"][component]["FC Connection"]["Type"] = serial # only one RC supported rc += 1 - elif component == 'Telemetry' and telem == 1: - self.data['Components'][component]['FC Connection']['Type'] = serial # only one telemetry supported - self.data['Components'][component]['FC Connection']['Protocol'] = protocol + elif component == "Telemetry" and telem == 1: + self.data["Components"][component]["FC Connection"]["Type"] = serial # only one telemetry supported + self.data["Components"][component]["FC Connection"]["Protocol"] = protocol telem += 1 - elif component == 'GNSS Receiver' and gnss == 1: - self.data['Components'][component]['FC Connection']['Type'] = serial # only one GNSS supported + elif component == "GNSS Receiver" and gnss == 1: + self.data["Components"][component]["FC Connection"]["Type"] = serial # only one GNSS supported gnss += 1 - elif component == 'ESC' and esc == 1: - self.data['Components'][component]['FC Connection']['Type'] = serial # only one ESC supported - self.data['Components'][component]['FC Connection']['Protocol'] = protocol + elif component == "ESC" and esc == 1: + self.data["Components"][component]["FC Connection"]["Type"] = serial # only one ESC supported + self.data["Components"][component]["FC Connection"]["Protocol"] = protocol esc += 1 return esc >= 2 def __set_esc_type_and_protocol_from_fc_parameters(self, fc_parameters: dict, doc: dict): - mot_pwm_type = fc_parameters['MOT_PWM_TYPE'] if "MOT_PWM_TYPE" in fc_parameters else 0 + mot_pwm_type = fc_parameters["MOT_PWM_TYPE"] if "MOT_PWM_TYPE" in fc_parameters else 0 try: mot_pwm_type = int(mot_pwm_type) except ValueError: logging_error(_("Invalid non-integer value for MOT_PWM_TYPE %f"), mot_pwm_type) mot_pwm_type = 0 - main_out_functions = [fc_parameters.get('SERVO' + str(i) + '_FUNCTION', 0) for i in range(1, 9)] + main_out_functions = [fc_parameters.get("SERVO" + str(i) + "_FUNCTION", 0) for i in range(1, 9)] # if any element of main_out_functions is in [33, 34, 35, 36] then ESC is connected to main_out if any(servo_function in [33, 34, 35, 36] for servo_function in main_out_functions): - self.data['Components']['ESC']['FC Connection']['Type'] = "Main Out" + self.data["Components"]["ESC"]["FC Connection"]["Type"] = "Main Out" else: - self.data['Components']['ESC']['FC Connection']['Type'] = "AIO" - self.data['Components']['ESC']['FC Connection']['Protocol'] = \ - doc['MOT_PWM_TYPE']['values'][str(mot_pwm_type)] + self.data["Components"]["ESC"]["FC Connection"]["Type"] = "AIO" + self.data["Components"]["ESC"]["FC Connection"]["Protocol"] = doc["MOT_PWM_TYPE"]["values"][str(mot_pwm_type)] def __set_battery_type_and_protocol_from_fc_parameters(self, fc_parameters: dict): if "BATT_MONITOR" in fc_parameters: batt_monitor = int(fc_parameters["BATT_MONITOR"]) - self.data['Components']['Battery Monitor']['FC Connection']['Type'] = \ - batt_monitor_connection[str(batt_monitor)].get('type') - self.data['Components']['Battery Monitor']['FC Connection']['Protocol'] = \ - batt_monitor_connection[str(batt_monitor)].get('protocol') + self.data["Components"]["Battery Monitor"]["FC Connection"]["Type"] = batt_monitor_connection[ + str(batt_monitor) + ].get("type") + self.data["Components"]["Battery Monitor"]["FC Connection"]["Protocol"] = batt_monitor_connection[ + str(batt_monitor) + ].get("protocol") def __set_motor_poles_from_fc_parameters(self, fc_parameters: dict): if "MOT_PWM_TYPE" in fc_parameters: mot_pwm_type_str = str(fc_parameters["MOT_PWM_TYPE"]) - if mot_pwm_type_str in mot_pwm_type_dict and mot_pwm_type_dict[mot_pwm_type_str].get('is_dshot', False): + if mot_pwm_type_str in mot_pwm_type_dict and mot_pwm_type_dict[mot_pwm_type_str].get("is_dshot", False): if "SERVO_BLH_POLES" in fc_parameters: - self.data['Components']['Motors']['Specifications']['Poles'] = fc_parameters["SERVO_BLH_POLES"] + self.data["Components"]["Motors"]["Specifications"]["Poles"] = fc_parameters["SERVO_BLH_POLES"] elif "SERVO_FTW_MASK" in fc_parameters and fc_parameters["SERVO_FTW_MASK"] and "SERVO_FTW_POLES" in fc_parameters: - self.data['Components']['Motors']['Specifications']['Poles'] = fc_parameters["SERVO_FTW_POLES"] + self.data["Components"]["Motors"]["Specifications"]["Poles"] = fc_parameters["SERVO_FTW_POLES"] def update_esc_protocol_combobox_entries(self, esc_connection_type): - """ Updates the ESC Protocol combobox entries based on the selected ESC Type.""" - if len(esc_connection_type) > 3 and esc_connection_type[:3] == 'CAN': - protocols = ['DroneCAN'] - elif len(esc_connection_type) > 6 and esc_connection_type[:6] == 'SERIAL': - protocols = [value['protocol'] for value in serial_protocols_dict.values() if value['component'] == 'ESC'] + """Updates the ESC Protocol combobox entries based on the selected ESC Type.""" + if len(esc_connection_type) > 3 and esc_connection_type[:3] == "CAN": + protocols = ["DroneCAN"] + elif len(esc_connection_type) > 6 and esc_connection_type[:6] == "SERIAL": + protocols = [value["protocol"] for value in serial_protocols_dict.values() if value["component"] == "ESC"] + elif "MOT_PWM_TYPE" in self.local_filesystem.doc_dict: + protocols = list(self.local_filesystem.doc_dict["MOT_PWM_TYPE"]["values"].values()) + elif "Q_M_PWM_TYPE" in self.local_filesystem.doc_dict: + protocols = list(self.local_filesystem.doc_dict["Q_M_PWM_TYPE"]["values"].values()) else: - if 'MOT_PWM_TYPE' in self.local_filesystem.doc_dict: - protocols = list(self.local_filesystem.doc_dict['MOT_PWM_TYPE']["values"].values()) - elif 'Q_M_PWM_TYPE' in self.local_filesystem.doc_dict: - protocols = list(self.local_filesystem.doc_dict['Q_M_PWM_TYPE']["values"].values()) - else: - protocols = [] + protocols = [] - protocol_path = ('ESC', 'FC Connection', 'Protocol') + protocol_path = ("ESC", "FC Connection", "Protocol") if protocol_path in self.entry_widgets: protocol_combobox = self.entry_widgets[protocol_path] - protocol_combobox['values'] = protocols # Update the combobox entries + protocol_combobox["values"] = protocols # Update the combobox entries if protocol_combobox.get() not in protocols: - protocol_combobox.set(protocols[0] if protocols else '') - protocol_combobox.update_idletasks() # re-draw the combobox ASAP + protocol_combobox.set(protocols[0] if protocols else "") + protocol_combobox.update_idletasks() # re-draw the combobox ASAP def add_entry_or_combobox(self, value, entry_frame, path): # Default values for comboboxes in case the apm.pdef.xml metadata is not available fallbacks = { - 'RC_PROTOCOLS': [value['protocol'] for value in rc_protocols_dict.values()], - 'BATT_MONITOR': [value['protocol'] for value in batt_monitor_connection.values()], - 'MOT_PWM_TYPE': [value['protocol'] for value in mot_pwm_type_dict.values()], - 'GPS_TYPE': [value['protocol'] for value in gnss_receiver_connection.values()], + "RC_PROTOCOLS": [value["protocol"] for value in rc_protocols_dict.values()], + "BATT_MONITOR": [value["protocol"] for value in batt_monitor_connection.values()], + "MOT_PWM_TYPE": [value["protocol"] for value in mot_pwm_type_dict.values()], + "GPS_TYPE": [value["protocol"] for value in gnss_receiver_connection.values()], } + def get_combobox_values(param_name: str) -> list: param_metadata = self.local_filesystem.doc_dict if param_name in param_metadata: @@ -457,40 +470,38 @@ def get_combobox_values(param_name: str) -> list: return [] combobox_config = { - ('Flight Controller', 'Firmware', 'Type'): { + ("Flight Controller", "Firmware", "Type"): { "values": VehicleComponents.supported_vehicles(), }, - ('RC Receiver', 'FC Connection', 'Type'): { - "values": ["RCin/SBUS"] + self.serial_ports + self.can_ports, + ("RC Receiver", "FC Connection", "Type"): { + "values": ["RCin/SBUS", *self.serial_ports, *self.can_ports], }, - ('RC Receiver', 'FC Connection', 'Protocol'): { - "values": get_combobox_values('RC_PROTOCOLS'), + ("RC Receiver", "FC Connection", "Protocol"): { + "values": get_combobox_values("RC_PROTOCOLS"), }, - ('Telemetry', 'FC Connection', 'Type'): { + ("Telemetry", "FC Connection", "Type"): { "values": self.serial_ports + self.can_ports, }, - ('Telemetry', 'FC Connection', 'Protocol'): { + ("Telemetry", "FC Connection", "Protocol"): { "values": ["MAVLink1", "MAVLink2", "MAVLink High Latency"], }, - ('Battery Monitor', 'FC Connection', 'Type'): { - "values": ['None', 'Analog', 'SPI', 'PWM'] + self.i2c_ports + self.serial_ports + self.can_ports, + ("Battery Monitor", "FC Connection", "Type"): { + "values": ["None", "Analog", "SPI", "PWM", *self.i2c_ports, *self.serial_ports, *self.can_ports], }, - ('Battery Monitor', 'FC Connection', 'Protocol'): { - "values": get_combobox_values('BATT_MONITOR'), + ("Battery Monitor", "FC Connection", "Protocol"): { + "values": get_combobox_values("BATT_MONITOR"), }, - ('ESC', 'FC Connection', 'Type'): { - "values": ['Main Out', 'AIO'] + self.serial_ports + self.can_ports, + ("ESC", "FC Connection", "Type"): { + "values": ["Main Out", "AIO", *self.serial_ports, *self.can_ports], }, - ('ESC', 'FC Connection', 'Protocol'): { - "values": get_combobox_values('MOT_PWM_TYPE') + ("ESC", "FC Connection", "Protocol"): {"values": get_combobox_values("MOT_PWM_TYPE")}, + ("GNSS Receiver", "FC Connection", "Type"): { + "values": ["None", *self.serial_ports, *self.can_ports], }, - ('GNSS Receiver', 'FC Connection', 'Type'): { - "values": ['None'] + self.serial_ports + self.can_ports, + ("GNSS Receiver", "FC Connection", "Protocol"): { + "values": get_combobox_values("GPS_TYPE"), }, - ('GNSS Receiver', 'FC Connection', 'Protocol'): { - "values": get_combobox_values('GPS_TYPE'), - }, - ('Battery', 'Specifications', 'Chemistry'): { + ("Battery", "Specifications", "Chemistry"): { "values": BatteryCell.chemistries(), }, } @@ -500,7 +511,7 @@ def get_combobox_values(param_name: str) -> list: cb.bind("", lambda event, path=path: self.validate_combobox(event, path)) cb.bind("", lambda event, path=path: self.validate_combobox(event, path)) - if path == ('ESC', 'FC Connection', 'Type'): # immediate update of ESC Protocol upon ESC Type selection + if path == ("ESC", "FC Connection", "Type"): # immediate update of ESC Protocol upon ESC Type selection cb.bind("<>", lambda event, path=path: self.update_esc_protocol_combobox_entries(cb.get())) cb.set(value) @@ -516,33 +527,33 @@ def get_combobox_values(param_name: str) -> list: def get_validate_function(self, entry, path): validate_functions = { - ('Frame', 'Specifications', 'TOW min Kg'): lambda event, entry=entry, path=path: - self.validate_entry_limits(event, entry, float, (0.01, 600), "Takeoff Weight", path), - - ('Frame', 'Specifications', 'TOW max Kg'): lambda event, entry=entry, path=path: - self.validate_entry_limits(event, entry, float, (0.01, 600), "Takeoff Weight", path), - - ('Battery', 'Specifications', 'Volt per cell max'): lambda event, entry=entry, path=path: - self.validate_cell_voltage(event, entry, path), - - ('Battery', 'Specifications', 'Volt per cell low'): lambda event, entry=entry, path=path: - self.validate_cell_voltage(event, entry, path), - - ('Battery', 'Specifications', 'Volt per cell crit'): lambda event, entry=entry, path=path: - self.validate_cell_voltage(event, entry, path), - - ('Battery', 'Specifications', 'Number of cells'): lambda event, entry=entry, path=path: - self.validate_entry_limits(event, entry, int, (1, 50), "Nr of cells", path), - - ('Battery', 'Specifications', 'Capacity mAh'): lambda event, entry=entry, path=path: - self.validate_entry_limits(event, entry, int, (100, 1000000), "mAh capacity", path), - - ('Motors', 'Specifications', 'Poles'): lambda event, entry=entry, path=path: - self.validate_entry_limits(event, entry, int, (3, 50), "Motor Poles", path), - - ('Propellers', 'Specifications', 'Diameter_inches'): lambda event, entry=entry, path=path: - self.validate_entry_limits(event, entry, float, (0.3, 400), "Propeller Diameter", path), - + ("Frame", "Specifications", "TOW min Kg"): lambda event, entry=entry, path=path: self.validate_entry_limits( + event, entry, float, (0.01, 600), "Takeoff Weight", path + ), + ("Frame", "Specifications", "TOW max Kg"): lambda event, entry=entry, path=path: self.validate_entry_limits( + event, entry, float, (0.01, 600), "Takeoff Weight", path + ), + ("Battery", "Specifications", "Volt per cell max"): lambda event, + entry=entry, + path=path: self.validate_cell_voltage(event, entry, path), + ("Battery", "Specifications", "Volt per cell low"): lambda event, + entry=entry, + path=path: self.validate_cell_voltage(event, entry, path), + ("Battery", "Specifications", "Volt per cell crit"): lambda event, + entry=entry, + path=path: self.validate_cell_voltage(event, entry, path), + ("Battery", "Specifications", "Number of cells"): lambda event, entry=entry, path=path: self.validate_entry_limits( + event, entry, int, (1, 50), "Nr of cells", path + ), + ("Battery", "Specifications", "Capacity mAh"): lambda event, entry=entry, path=path: self.validate_entry_limits( + event, entry, int, (100, 1000000), "mAh capacity", path + ), + ("Motors", "Specifications", "Poles"): lambda event, entry=entry, path=path: self.validate_entry_limits( + event, entry, int, (3, 50), "Motor Poles", path + ), + ("Propellers", "Specifications", "Diameter_inches"): lambda event, + entry=entry, + path=path: self.validate_entry_limits(event, entry, float, (0.3, 400), "Propeller Diameter", path), } return validate_functions.get(path, None) @@ -550,20 +561,20 @@ def validate_combobox(self, event, path) -> bool: """ Validates the value of a combobox. """ - combobox = event.widget # Get the combobox widget that triggered the event - value = combobox.get() # Get the current value of the combobox - allowed_values = combobox.cget("values") # Get the list of allowed values + combobox = event.widget # Get the combobox widget that triggered the event + value = combobox.get() # Get the current value of the combobox + allowed_values = combobox.cget("values") # Get the list of allowed values if value not in allowed_values: - if event.type == "10": # FocusOut events - _paths_str = '>'.join(list(path)) - _allowed_str = ', '.join(allowed_values) + if event.type == "10": # FocusOut events + _paths_str = ">".join(list(path)) + _allowed_str = ", ".join(allowed_values) error_msg = _("Invalid value '{value}' for {_paths_str}\nAllowed values are: {_allowed_str}") show_error_message(_("Error"), error_msg.format(**locals())) combobox.configure(style="comb_input_invalid.TCombobox") return False - if path == ('ESC', 'FC Connection', 'Type'): + if path == ("ESC", "FC Connection", "Type"): self.update_esc_protocol_combobox_entries(value) combobox.configure(style="comb_input_valid.TCombobox") @@ -580,7 +591,7 @@ def validate_entry_limits(self, event, entry, data_type, limits, _name, path): raise ValueError(error_msg.format(**locals())) except ValueError as _e: if is_focusout_event: - _paths_str = '>'.join(list(path)) + _paths_str = ">".join(list(path)) error_msg = _("Invalid value '{value}' for {_paths_str}\n{e}") show_error_message(_("Error"), error_msg.format(**locals())) return False @@ -591,7 +602,7 @@ def validate_cell_voltage(self, event, entry, path): # pylint: disable=too-many """ Validates the value of a battery cell voltage entry. """ - chemistry_path = ('Battery', 'Specifications', 'Chemistry') + chemistry_path = ("Battery", "Specifications", "Chemistry") if chemistry_path not in self.entry_widgets: show_error_message(_("Error"), _("Battery Chemistry not set. Will default to Lipo.")) chemistry = "Lipo" @@ -599,7 +610,7 @@ def validate_cell_voltage(self, event, entry, path): # pylint: disable=too-many chemistry = self.entry_widgets[chemistry_path].get() value = entry.get() is_focusout_event = event and event.type == "10" - _path_str = '>'.join(list(path)) + _path_str = ">".join(list(path)) try: voltage = float(value) volt_limit = BatteryCell.limit_min_voltage(chemistry) @@ -654,26 +665,30 @@ def validate_data(self): # pylint: disable=too-many-branches for path, entry in self.entry_widgets.items(): value = entry.get() - _path_str = '>'.join(list(path)) + _path_str = ">".join(list(path)) if isinstance(entry, ttk.Combobox): - if path == ('ESC', 'FC Connection', 'Type'): + if path == ("ESC", "FC Connection", "Type"): self.update_esc_protocol_combobox_entries(value) if value not in entry.cget("values"): - _values_str = ', '.join(entry.cget('values')) + _values_str = ", ".join(entry.cget("values")) error_msg = _("Invalid value '{value}' for {_path_str}\nAllowed values are: {_values_str}") show_error_message(_("Error"), error_msg.format(**locals())) entry.configure(style="comb_input_invalid.TCombobox") invalid_values = True continue - if 'FC Connection' in path and 'Type' in path: + if "FC Connection" in path and "Type" in path: if value in fc_serial_connection and value not in ["CAN1", "CAN2", "I2C1", "I2C2", "I2C3", "I2C4"]: - if path[0] in ['Telemetry', 'RC Receiver'] and \ - fc_serial_connection[value] in ['Telemetry', 'RC Receiver']: + if path[0] in ["Telemetry", "RC Receiver"] and fc_serial_connection[value] in [ + "Telemetry", + "RC Receiver", + ]: entry.configure(style="comb_input_valid.TCombobox") continue # Allow telemetry and RC Receiver connections using the same SERIAL port - if self.data['Components']['Battery Monitor']['FC Connection']['Protocol'] == 'ESC' and \ - path[0] in ['Battery Monitor', 'ESC'] and \ - fc_serial_connection[value] in ['Battery Monitor', 'ESC']: + if ( + self.data["Components"]["Battery Monitor"]["FC Connection"]["Protocol"] == "ESC" + and path[0] in ["Battery Monitor", "ESC"] + and fc_serial_connection[value] in ["Battery Monitor", "ESC"] + ): entry.configure(style="comb_input_valid.TCombobox") continue # Allow 'Battery Monitor' and 'ESC' connections using the same SERIAL port error_msg = _("Duplicate FC connection type '{value}' for {_path_str}") @@ -686,20 +701,23 @@ def validate_data(self): # pylint: disable=too-many-branches validate_function = self.get_validate_function(entry, path) if validate_function: - mock_focus_out_event = type('', (), {'type': '10'})() + mock_focus_out_event = type("", (), {"type": "10"})() if not validate_function(mock_focus_out_event): invalid_values = True - if path in [('Battery', 'Specifications', 'Volt per cell max'), ('Battery', 'Specifications', 'Volt per cell low'), - ('Battery', 'Specifications', 'Volt per cell crit')]: + if path in [ + ("Battery", "Specifications", "Volt per cell max"), + ("Battery", "Specifications", "Volt per cell low"), + ("Battery", "Specifications", "Volt per cell crit"), + ]: if not self.validate_cell_voltage(None, entry, path): invalid_values = True - if path == ('Battery', 'Specifications', 'Volt per cell low'): - if value >= self.entry_widgets[('Battery', 'Specifications', 'Volt per cell max')].get(): + if path == ("Battery", "Specifications", "Volt per cell low"): + if value >= self.entry_widgets[("Battery", "Specifications", "Volt per cell max")].get(): show_error_message(_("Error"), _("Battery Cell Low voltage must be lower than max voltage")) entry.configure(style="entry_input_invalid.TEntry") invalid_values = True - if path == ('Battery', 'Specifications', 'Volt per cell crit'): - if value >= self.entry_widgets[('Battery', 'Specifications', 'Volt per cell low')].get(): + if path == ("Battery", "Specifications", "Volt per cell crit"): + if value >= self.entry_widgets[("Battery", "Specifications", "Volt per cell low")].get(): show_error_message(_("Error"), _("Battery Cell Crit voltage must be lower than low voltage")) entry.configure(style="entry_input_invalid.TEntry") invalid_values = True @@ -710,7 +728,7 @@ def validate_data(self): # pylint: disable=too-many-branches if __name__ == "__main__": args = argument_parser() - logging_basicConfig(level=logging_getLevelName(args.loglevel), format='%(asctime)s - %(levelname)s - %(message)s') + logging_basicConfig(level=logging_getLevelName(args.loglevel), format="%(asctime)s - %(levelname)s - %(message)s") filesystem = LocalFilesystem(args.vehicle_dir, args.vehicle_type, None, args.allow_editing_template_files) app = ComponentEditorWindow(VERSION, filesystem) diff --git a/MethodicConfigurator/frontend_tkinter_component_editor_base.py b/MethodicConfigurator/frontend_tkinter_component_editor_base.py index 24290aa..768fa9b 100644 --- a/MethodicConfigurator/frontend_tkinter_component_editor_base.py +++ b/MethodicConfigurator/frontend_tkinter_component_editor_base.py @@ -1,37 +1,33 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" +import tkinter as tk from argparse import ArgumentParser - from logging import basicConfig as logging_basicConfig from logging import getLevelName as logging_getLevelName + # from logging import debug as logging_debug from logging import info as logging_info - -import tkinter as tk -from tkinter import ttk -from tkinter import messagebox - -from MethodicConfigurator.common_arguments import add_common_arguments_and_parse +from tkinter import messagebox, ttk from MethodicConfigurator.backend_filesystem import LocalFilesystem - -from MethodicConfigurator.frontend_tkinter_base import show_tooltip -from MethodicConfigurator.frontend_tkinter_base import show_error_message -from MethodicConfigurator.frontend_tkinter_base import ScrollFrame -from MethodicConfigurator.frontend_tkinter_base import BaseWindow -from MethodicConfigurator.frontend_tkinter_base import RichText -from MethodicConfigurator.frontend_tkinter_base import UsagePopupWindow - -from MethodicConfigurator.internationalization import _ - +from MethodicConfigurator.common_arguments import add_common_arguments_and_parse +from MethodicConfigurator.frontend_tkinter_base import ( + BaseWindow, + RichText, + ScrollFrame, + UsagePopupWindow, + show_error_message, + show_tooltip, +) +from MethodicConfigurator import _ from MethodicConfigurator.version import VERSION @@ -44,11 +40,17 @@ def argument_parser(): Returns: argparse.Namespace: An object containing the parsed arguments. """ - parser = ArgumentParser(description=_('A GUI for editing JSON files that contain vehicle component configurations. ' - 'Not to be used directly, but through the main ArduPilot methodic configurator script.')) + # pylint: disable=duplicate-code + parser = ArgumentParser( + description=_( + "A GUI for editing JSON files that contain vehicle component configurations. " + "Not to be used directly, but through the main ArduPilot methodic configurator script." + ) + ) parser = LocalFilesystem.add_argparse_arguments(parser) parser = ComponentEditorWindowBase.add_argparse_arguments(parser) return add_common_arguments_and_parse(parser) + # pylint: enable=duplicate-code class ComponentEditorWindowBase(BaseWindow): @@ -59,20 +61,21 @@ class ComponentEditorWindowBase(BaseWindow): contain vehicle component configurations. It inherits from the BaseWindow class, which provides basic window functionality. """ - def __init__(self, version, local_filesystem: LocalFilesystem=None): + + def __init__(self, version, local_filesystem: LocalFilesystem = None): super().__init__() self.local_filesystem = local_filesystem self.root.title(_("Amilcar Lucas's - ArduPilot methodic configurator ") + version + _(" - Vehicle Component Editor")) - self.root.geometry("880x600") # Set the window width + self.root.geometry("880x600") # Set the window width self.data = local_filesystem.load_vehicle_components_json_data(local_filesystem.vehicle_dir) if len(self.data) < 1: # Schedule the window to be destroyed after the mainloop has started - self.root.after(100, self.root.destroy) # Adjust the delay as needed + self.root.after(100, self.root.destroy) # Adjust the delay as needed return - self.entry_widgets = {} # Dictionary for entry widgets + self.entry_widgets = {} # Dictionary for entry widgets intro_frame = ttk.Frame(self.main_frame) intro_frame.pack(side=tk.TOP, fill="x", expand=False) @@ -118,8 +121,9 @@ def __display_component_editor_usage_instructions(parent: tk.Tk): usage_popup_window = BaseWindow(parent) style = ttk.Style() - instructions_text = RichText(usage_popup_window.main_frame, wrap=tk.WORD, height=5, bd=0, - background=style.lookup("TLabel", "background")) + instructions_text = RichText( + usage_popup_window.main_frame, wrap=tk.WORD, height=5, bd=0, background=style.lookup("TLabel", "background") + ) instructions_text.insert(tk.END, _("1. Describe ")) instructions_text.insert(tk.END, _("all"), "bold") instructions_text.insert(tk.END, _(" vehicle component properties in the window below\n")) @@ -134,15 +138,21 @@ def __display_component_editor_usage_instructions(parent: tk.Tk): instructions_text.insert(tk.END, _(" only after all information is correct")) instructions_text.config(state=tk.DISABLED) - UsagePopupWindow.display(parent, usage_popup_window, _("How to use the component editor window"), - "component_editor", "690x200", instructions_text) + UsagePopupWindow.display( + parent, + usage_popup_window, + _("How to use the component editor window"), + "component_editor", + "690x200", + instructions_text, + ) def update_json_data(self): # should be overwritten in child classes - if 'Format version' not in self.data: - self.data['Format version'] = 1 + if "Format version" not in self.data: + self.data["Format version"] = 1 def _set_component_value_and_update_ui(self, path: tuple, value: str): - data_path = self.data['Components'] + data_path = self.data["Components"] for key in path[:-1]: data_path = data_path[key] data_path[path[-1]] = value @@ -169,7 +179,7 @@ def __add_widget(self, parent, key, value, path): value (dict): The value associated with the key. path (list): The path to the current key in the JSON data. """ - if isinstance(value, dict): # JSON non-leaf elements, add LabelFrame widget + if isinstance(value, dict): # JSON non-leaf elements, add LabelFrame widget frame = ttk.LabelFrame(parent, text=key) is_toplevel = parent == self.scroll_frame.view_port side = tk.TOP if is_toplevel else tk.LEFT @@ -178,28 +188,30 @@ def __add_widget(self, parent, key, value, path): frame.pack(fill=tk.X, side=side, pady=pady, padx=5, anchor=anchor) for sub_key, sub_value in value.items(): # recursively add child elements - self.__add_widget(frame, sub_key, sub_value, path + [key]) - else: # JSON leaf elements, add Entry widget + self.__add_widget(frame, sub_key, sub_value, [*path, key]) + else: # JSON leaf elements, add Entry widget entry_frame = ttk.Frame(parent) entry_frame.pack(side=tk.TOP, fill=tk.X, pady=(0, 5)) label = ttk.Label(entry_frame, text=key) label.pack(side=tk.LEFT) - entry = self.add_entry_or_combobox(value, entry_frame, tuple(path+[key])) + entry = self.add_entry_or_combobox(value, entry_frame, tuple([*path, key])) entry.pack(side=tk.LEFT, expand=True, fill=tk.X, padx=(0, 5)) # Store the entry widget in the entry_widgets dictionary for later retrieval - self.entry_widgets[tuple(path+[key])] = entry + self.entry_widgets[tuple([*path, key])] = entry def save_data(self): """ Saves the edited JSON data back to the file. """ - confirm_message = _("ArduPilot Methodic Configurator only operates correctly if all component properties are correct." - " ArduPilot parameter values depend on the components used and their connections." - " Have you used the scrollbar on the right side of the window and " - "entered the correct values for all components?") + confirm_message = _( + "ArduPilot Methodic Configurator only operates correctly if all component properties are correct." + " ArduPilot parameter values depend on the components used and their connections." + " Have you used the scrollbar on the right side of the window and " + "entered the correct values for all components?" + ) user_confirmation = messagebox.askyesno(_("Confirm that all component properties are correct"), confirm_message) if not user_confirmation: @@ -241,17 +253,21 @@ def add_entry_or_combobox(self, value, entry_frame, path): # pylint: disable=un @staticmethod def add_argparse_arguments(parser): - parser.add_argument('--skip-component-editor', - action='store_true', - help=_('Skip the component editor window. Only use this if all components have been configured. ' - 'Default to false')) + parser.add_argument( + "--skip-component-editor", + action="store_true", + help=_( + "Skip the component editor window. Only use this if all components have been configured. " + "Defaults to %(default)s" + ), + ) return parser if __name__ == "__main__": args = argument_parser() - logging_basicConfig(level=logging_getLevelName(args.loglevel), format='%(asctime)s - %(levelname)s - %(message)s') + logging_basicConfig(level=logging_getLevelName(args.loglevel), format="%(asctime)s - %(levelname)s - %(message)s") filesystem = LocalFilesystem(args.vehicle_dir, args.vehicle_type, None, args.allow_editing_template_files) app = ComponentEditorWindowBase(VERSION, filesystem) diff --git a/MethodicConfigurator/frontend_tkinter_connection_selection.py b/MethodicConfigurator/frontend_tkinter_connection_selection.py index 42ac2f6..3a22be3 100644 --- a/MethodicConfigurator/frontend_tkinter_connection_selection.py +++ b/MethodicConfigurator/frontend_tkinter_connection_selection.py @@ -1,55 +1,52 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' - -from sys import exit as sys_exit +""" +import tkinter as tk from argparse import ArgumentParser - from logging import basicConfig as logging_basicConfig -from logging import getLevelName as logging_getLevelName from logging import debug as logging_debug +from logging import getLevelName as logging_getLevelName from logging import warning as logging_warning - -import tkinter as tk -from tkinter import ttk -from tkinter import simpledialog - -from MethodicConfigurator.common_arguments import add_common_arguments_and_parse +from sys import exit as sys_exit +from tkinter import simpledialog, ttk from MethodicConfigurator.backend_flightcontroller import FlightController - -from MethodicConfigurator.frontend_tkinter_base import show_no_connection_error -from MethodicConfigurator.frontend_tkinter_base import show_tooltip -from MethodicConfigurator.frontend_tkinter_base import ProgressWindow -from MethodicConfigurator.frontend_tkinter_base import BaseWindow - +from MethodicConfigurator.common_arguments import add_common_arguments_and_parse +from MethodicConfigurator.frontend_tkinter_base import BaseWindow, ProgressWindow, show_no_connection_error, show_tooltip from MethodicConfigurator.frontend_tkinter_pair_tuple_combobox import PairTupleCombobox - -from MethodicConfigurator.internationalization import _ +from MethodicConfigurator import _ -class ConnectionSelectionWidgets(): # pylint: disable=too-many-instance-attributes +class ConnectionSelectionWidgets: # pylint: disable=too-many-instance-attributes """ A class for managing the selection of flight controller connections in the GUI. This class provides functionality for displaying available flight controller connections, allowing the user to select a connection, and handling the connection process. """ - def __init__(self, parent, parent_frame, flight_controller: FlightController, # pylint: disable=too-many-arguments - destroy_parent_on_connect: bool, download_params_on_connect: bool): + + def __init__( # pylint: disable=too-many-arguments + self, + parent, + parent_frame, + flight_controller: FlightController, + destroy_parent_on_connect: bool, + download_params_on_connect: bool, + ): self.parent = parent self.flight_controller = flight_controller self.destroy_parent_on_connect = destroy_parent_on_connect self.download_params_on_connect = download_params_on_connect - self.previous_selection = flight_controller.comport.device if hasattr(self.flight_controller.comport, "device") \ - else None + self.previous_selection = ( + flight_controller.comport.device if hasattr(self.flight_controller.comport, "device") else None + ) self.connection_progress_window = None # Create a new frame for the flight controller connection selection label and combobox @@ -57,24 +54,29 @@ def __init__(self, parent, parent_frame, flight_controller: FlightController, # # Create a description label for the flight controller connection selection conn_selection_label = ttk.Label(self.container_frame, text=_("flight controller connection:")) - conn_selection_label.pack(side=tk.TOP) # Add the label to the top of the conn_selection_frame + conn_selection_label.pack(side=tk.TOP) # Add the label to the top of the conn_selection_frame # Create a read-only combobox for flight controller connection selection - self.conn_selection_combobox = PairTupleCombobox(self.container_frame, self.flight_controller.get_connection_tuples(), - self.previous_selection, - "FC connection", - state='readonly') - self.conn_selection_combobox.bind("<>", self.on_select_connection_combobox_change, '+') + self.conn_selection_combobox = PairTupleCombobox( + self.container_frame, + self.flight_controller.get_connection_tuples(), + self.previous_selection, + "FC connection", + state="readonly", + ) + self.conn_selection_combobox.bind("<>", self.on_select_connection_combobox_change, "+") self.conn_selection_combobox.pack(side=tk.TOP, pady=(4, 0)) - show_tooltip(self.conn_selection_combobox, _("Select the flight controller connection\nYou can add a custom " - "connection to the existing ones")) + show_tooltip( + self.conn_selection_combobox, + _("Select the flight controller connection\nYou can add a custom connection to the existing ones"), + ) def on_select_connection_combobox_change(self, _event): selected_connection = self.conn_selection_combobox.get_selected_key() error_msg = _("Connection combobox changed to: {selected_connection}") logging_debug(error_msg.format(**locals())) if self.flight_controller.master is None or selected_connection != self.flight_controller.comport.device: - if selected_connection == 'Add another': + if selected_connection == "Add another": if not self.add_connection() and self.previous_selection: # nothing got selected revert to the current connection self.conn_selection_combobox.set(self.previous_selection) @@ -83,12 +85,16 @@ def on_select_connection_combobox_change(self, _event): def add_connection(self): # Open the connection selection dialog - selected_connection = simpledialog.askstring(_("Flight Controller Connection"), - _("Enter the connection string to the flight controller. " - "Examples are:\n\nCOM4 (on windows)\n" - "/dev/serial/by-id/usb-xxx (on linux)\n" - "tcp:127.0.0.1:5761\n" - "udp:127.0.0.1:14551")) + selected_connection = simpledialog.askstring( + _("Flight Controller Connection"), + _( + "Enter the connection string to the flight controller. " + "Examples are:\n\nCOM4 (on windows)\n" + "/dev/serial/by-id/usb-xxx (on linux)\n" + "tcp:127.0.0.1:5761\n" + "udp:127.0.0.1:14551" + ), + ) if selected_connection: error_msg = _("Will add new connection: {selected_connection} if not duplicated") logging_debug(error_msg.format(**locals())) @@ -104,10 +110,12 @@ def add_connection(self): return selected_connection def reconnect(self, selected_connection: str = ""): # defaults to auto-connect - self.connection_progress_window = ProgressWindow(self.parent.root, _("Connecting with the FC"), - _("Connection step {} of {}")) - error_message = self.flight_controller.connect(selected_connection, - self.connection_progress_window.update_progress_bar) + self.connection_progress_window = ProgressWindow( + self.parent.root, _("Connecting with the FC"), _("Connection step {} of {}") + ) + error_message = self.flight_controller.connect( + selected_connection, self.connection_progress_window.update_progress_bar + ) if error_message: show_no_connection_error(error_message) return True @@ -129,31 +137,41 @@ class ConnectionSelectionWindow(BaseWindow): It inherits from the BaseWindow class and uses the ConnectionSelectionWidgets class to handle the UI elements related to connection selection. """ + def __init__(self, flight_controller: FlightController, connection_result_string: str): super().__init__() self.root.title(_("Flight controller connection")) - self.root.geometry("460x450") # Set the window size + self.root.geometry("460x450") # Set the window size # Explain why we are here if flight_controller.comport is None: introduction_text = _("No ArduPilot flight controller was auto-detected detected yet.") + elif ":" in connection_result_string: + introduction_text = connection_result_string.replace(":", ":\n") else: - if ":" in connection_result_string: - introduction_text = connection_result_string.replace(":", ":\n") - else: - introduction_text = connection_result_string - self.introduction_label = ttk.Label(self.main_frame, anchor=tk.CENTER, justify=tk.CENTER, - text=introduction_text + _("\nChoose one of the following three options:")) + introduction_text = connection_result_string + self.introduction_label = ttk.Label( + self.main_frame, + anchor=tk.CENTER, + justify=tk.CENTER, + text=introduction_text + _("\nChoose one of the following three options:"), + ) self.introduction_label.pack(expand=False, fill=tk.X, padx=6, pady=6) # Option 1 - Auto-connect option1_label = ttk.Label(text=_("Auto connection"), style="Bold.TLabel") option1_label_frame = ttk.LabelFrame(self.main_frame, labelwidget=option1_label, borderwidth=2, relief="solid") option1_label_frame.pack(expand=False, fill=tk.X, padx=6, pady=6) - option1_label = ttk.Label(option1_label_frame, anchor=tk.CENTER, justify=tk.CENTER, - text=_("Connect a flight controller to the PC,\n" - "wait 7 seconds for it to fully boot and\n" - "press the Auto-connect button below to connect to it")) + option1_label = ttk.Label( + option1_label_frame, + anchor=tk.CENTER, + justify=tk.CENTER, + text=_( + "Connect a flight controller to the PC,\n" + "wait 7 seconds for it to fully boot and\n" + "press the Auto-connect button below to connect to it" + ), + ) option1_label.pack(expand=False, fill=tk.X, padx=6) autoconnect_button = ttk.Button(option1_label_frame, text=_("Auto-connect"), command=self.fc_autoconnect) autoconnect_button.pack(expand=False, fill=tk.X, padx=100, pady=6) @@ -163,35 +181,48 @@ def __init__(self, flight_controller: FlightController, connection_result_string option2_label = ttk.Label(text=_("Manual connection"), style="Bold.TLabel") option2_label_frame = ttk.LabelFrame(self.main_frame, labelwidget=option2_label, borderwidth=2, relief="solid") option2_label_frame.pack(expand=False, fill=tk.X, padx=6, pady=6) - option2_label = ttk.Label(option2_label_frame, anchor=tk.CENTER, justify=tk.CENTER, - text=_("Connect a flight controller to the PC,\n" - "wait 7 seconds for it to fully boot and\n" - "manually select the fight controller connection or add a new one")) + # pylint: disable=duplicate-code + option2_label = ttk.Label( + option2_label_frame, + anchor=tk.CENTER, + justify=tk.CENTER, + text=_( + "Connect a flight controller to the PC,\n" + "wait 7 seconds for it to fully boot and\n" + "manually select the fight controller connection or add a new one" + ), + ) + # pylint: enable=duplicate-code option2_label.pack(expand=False, fill=tk.X, padx=6) - self.connection_selection_widgets = ConnectionSelectionWidgets(self, option2_label_frame, flight_controller, - destroy_parent_on_connect=True, - download_params_on_connect=False) + self.connection_selection_widgets = ConnectionSelectionWidgets( + self, option2_label_frame, flight_controller, destroy_parent_on_connect=True, download_params_on_connect=False + ) self.connection_selection_widgets.container_frame.pack(expand=False, fill=tk.X, padx=80, pady=6) # Option 3 - Skip FC connection, just edit the .param files on disk option3_label = ttk.Label(text=_("No connection"), style="Bold.TLabel") option3_label_frame = ttk.LabelFrame(self.main_frame, labelwidget=option3_label, borderwidth=2, relief="solid") option3_label_frame.pack(expand=False, fill=tk.X, padx=6, pady=6) - #option3_label = ttk.Label(option3_label_frame, anchor=tk.CENTER, justify=tk.CENTER, + # option3_label = ttk.Label(option3_label_frame, anchor=tk.CENTER, justify=tk.CENTER, # text=_("Skip the flight controller connection,\n") # "no default parameter values will be fetched from the FC,\n" # "default parameter values from disk will be used instead\n" # "(if '00_default.param' file is present)\n" # "and just edit the intermediate '.param' files on disk") - #option3_label.pack(expand=False, fill=tk.X, padx=6) - skip_fc_connection_button = ttk.Button(option3_label_frame, - text=_("Skip FC connection, just edit the .param files on disk"), - command=lambda flight_controller=flight_controller: - self.skip_fc_connection(flight_controller)) + # option3_label.pack(expand=False, fill=tk.X, padx=6) + skip_fc_connection_button = ttk.Button( + option3_label_frame, + text=_("Skip FC connection, just edit the .param files on disk"), + command=lambda flight_controller=flight_controller: self.skip_fc_connection(flight_controller), + ) skip_fc_connection_button.pack(expand=False, fill=tk.X, padx=15, pady=6) - show_tooltip(skip_fc_connection_button, - _("No parameter values will be fetched from the FC, default parameter values from disk will be used\n" - "instead (if '00_default.param' file is present) and just edit the intermediate '.param' files on disk")) + show_tooltip( + skip_fc_connection_button, + _( + "No parameter values will be fetched from the FC, default parameter values from disk will be used\n" + "instead (if '00_default.param' file is present) and just edit the intermediate '.param' files on disk" + ), + ) # Bind the close_connection_and_quit function to the window close event self.root.protocol("WM_DELETE_WINDOW", self.close_and_quit) @@ -218,27 +249,37 @@ def argument_parser(): Returns: argparse.Namespace: An object containing the parsed arguments. """ - parser = ArgumentParser(description=_('This main is for testing and development only. ' - 'Usually, the ConnectionSelectionWidgets is called from another script')) + parser = ArgumentParser( + description=_( + "This main is for testing and development only. " + "Usually, the ConnectionSelectionWidgets is called from another script" + ) + ) parser = FlightController.add_argparse_arguments(parser) return add_common_arguments_and_parse(parser) +# pylint: disable=duplicate-code def main(): args = argument_parser() - logging_basicConfig(level=logging_getLevelName(args.loglevel), format='%(asctime)s - %(levelname)s - %(message)s') + logging_basicConfig(level=logging_getLevelName(args.loglevel), format="%(asctime)s - %(levelname)s - %(message)s") - logging_warning(_("This main is for testing and development only, usually the ConnectionSelectionWindow is called from " - "another script")) + logging_warning( + _( + "This main is for testing and development only, usually the ConnectionSelectionWindow is called from " + "another script" + ) + ) + # pylint: enable=duplicate-code - flight_controller = FlightController(args.reboot_time) # Initialize your FlightController instance - result = flight_controller.connect(device=args.device) # Connect to the flight controller + flight_controller = FlightController(args.reboot_time) # Initialize your FlightController instance + result = flight_controller.connect(device=args.device) # Connect to the flight controller if result: logging_warning(result) window = ConnectionSelectionWindow(flight_controller, result) window.root.mainloop() - flight_controller.disconnect() # Disconnect from the flight controller + flight_controller.disconnect() # Disconnect from the flight controller if __name__ == "__main__": diff --git a/MethodicConfigurator/frontend_tkinter_directory_selection.py b/MethodicConfigurator/frontend_tkinter_directory_selection.py index 698b26b..fc71772 100644 --- a/MethodicConfigurator/frontend_tkinter_directory_selection.py +++ b/MethodicConfigurator/frontend_tkinter_directory_selection.py @@ -1,48 +1,34 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' - +""" +import tkinter as tk from argparse import ArgumentParser - -from sys import exit as sys_exit - from copy import deepcopy - from logging import basicConfig as logging_basicConfig +from logging import debug as logging_error from logging import getLevelName as logging_getLevelName -from logging import warning as logging_warning from logging import info as logging_info -from logging import debug as logging_error - -import tkinter as tk -from tkinter import messagebox -from tkinter import ttk -from tkinter import filedialog - -from MethodicConfigurator.version import VERSION - -from MethodicConfigurator.common_arguments import add_common_arguments_and_parse +from logging import warning as logging_warning +from sys import exit as sys_exit +from tkinter import filedialog, messagebox, ttk from MethodicConfigurator.backend_filesystem import LocalFilesystem from MethodicConfigurator.backend_filesystem_program_settings import ProgramSettings - -from MethodicConfigurator.frontend_tkinter_base import show_no_param_files_error -from MethodicConfigurator.frontend_tkinter_base import show_tooltip -from MethodicConfigurator.frontend_tkinter_base import BaseWindow - +from MethodicConfigurator.common_arguments import add_common_arguments_and_parse +from MethodicConfigurator.frontend_tkinter_base import BaseWindow, show_no_param_files_error, show_tooltip from MethodicConfigurator.frontend_tkinter_template_overview import TemplateOverviewWindow - -from MethodicConfigurator.internationalization import _ +from MethodicConfigurator import _ +from MethodicConfigurator.version import VERSION -class DirectorySelectionWidgets(): +class DirectorySelectionWidgets: """ A class to manage directory selection widgets in the GUI. @@ -50,9 +36,18 @@ class DirectorySelectionWidgets(): including a label, an entry field for displaying the selected directory, and a button for opening a directory selection dialog. """ - def __init__(self, parent, parent_frame, initialdir: str, label_text: str, # pylint: disable=too-many-arguments - autoresize_width: bool, dir_tooltip: str, button_tooltip: str, - is_template_selection: bool): + + def __init__( # pylint: disable=too-many-arguments + self, + parent, + parent_frame, + initialdir: str, + label_text: str, + autoresize_width: bool, + dir_tooltip: str, + button_tooltip: str, + is_template_selection: bool, + ): self.parent = parent self.directory = deepcopy(initialdir) self.label_text = label_text @@ -73,7 +68,7 @@ def __init__(self, parent, parent_frame, initialdir: str, label_text: str, # py # Create a read-only entry for the directory dir_var = tk.StringVar(value=self.directory) - self.directory_entry = tk.Entry(directory_selection_subframe, textvariable=dir_var, state='readonly') + self.directory_entry = tk.Entry(directory_selection_subframe, textvariable=dir_var, state="readonly") if autoresize_width: self.directory_entry.config(width=max(4, len(self.directory))) self.directory_entry.pack(side=tk.LEFT, fill="x", expand=True, anchor=tk.NW, pady=(4, 0)) @@ -81,8 +76,9 @@ def __init__(self, parent, parent_frame, initialdir: str, label_text: str, # py if button_tooltip: # Create a button for directory selection - directory_selection_button = ttk.Button(directory_selection_subframe, text="...", - command=self.on_select_directory, width=2) + directory_selection_button = ttk.Button( + directory_selection_subframe, text="...", command=self.on_select_directory, width=2 + ) directory_selection_button.pack(side=tk.RIGHT, anchor=tk.NW) show_tooltip(directory_selection_button, button_tooltip) else: @@ -100,12 +96,12 @@ def on_select_directory(self): if selected_directory: if self.autoresize_width: # Set the width of the directory_entry to match the width of the selected_directory text - self.directory_entry.config(width=max(4, len(selected_directory)), state='normal') + self.directory_entry.config(width=max(4, len(selected_directory)), state="normal") else: - self.directory_entry.config(state='normal') + self.directory_entry.config(state="normal") self.directory_entry.delete(0, tk.END) self.directory_entry.insert(0, selected_directory) - self.directory_entry.config(state='readonly') + self.directory_entry.config(state="readonly") self.parent.root.update_idletasks() self.directory = selected_directory return True @@ -115,13 +111,14 @@ def get_selected_directory(self): return self.directory -class DirectoryNameWidgets(): # pylint: disable=too-few-public-methods +class DirectoryNameWidgets: # pylint: disable=too-few-public-methods """ A class to manage directory name selection widgets in the GUI. This class provides functionality for creating and managing widgets related to directory name selection, including a label and an entry field for displaying the selected directory name. """ + def __init__(self, parent_frame, initial_dir: str, label_text: str, dir_tooltip: str): # Create a new frame for the directory name selection label self.container_frame = ttk.Frame(parent_frame) @@ -133,8 +130,7 @@ def __init__(self, parent_frame, initial_dir: str, label_text: str, dir_tooltip: # Create an entry for the directory self.dir_var = tk.StringVar(value=initial_dir) - directory_entry = ttk.Entry(self.container_frame, textvariable=self.dir_var, - width=max(4, len(initial_dir))) + directory_entry = ttk.Entry(self.container_frame, textvariable=self.dir_var, width=max(4, len(initial_dir))) directory_entry.pack(side=tk.LEFT, fill="x", expand=True, anchor=tk.NW, pady=(4, 0)) show_tooltip(directory_entry, dir_tooltip) @@ -149,18 +145,34 @@ class VehicleDirectorySelectionWidgets(DirectorySelectionWidgets): directory selections. It includes additional logic for updating the local filesystem with the selected vehicle directory and re-initializing the filesystem with the new directory. """ - def __init__(self, parent: ttk, parent_frame: ttk.Frame, # pylint: disable=too-many-arguments - local_filesystem: LocalFilesystem, - initial_dir: str, destroy_parent_on_open: bool) -> None: + + def __init__( # pylint: disable=too-many-arguments + self, + parent: ttk, + parent_frame: ttk.Frame, + local_filesystem: LocalFilesystem, + initial_dir: str, + destroy_parent_on_open: bool, + ) -> None: # Call the parent constructor with the necessary arguments - super().__init__(parent, parent_frame, initial_dir, _("Vehicle configuration directory:"), - False, - _("Vehicle-specific directory containing the intermediate\n" - "parameter files to be uploaded to the flight controller"), - _("Select the vehicle-specific configuration directory containing the\n" - "intermediate parameter files to be uploaded to the flight controller") \ - if destroy_parent_on_open else '', - False) + super().__init__( + parent, + parent_frame, + initial_dir, + _("Vehicle configuration directory:"), + False, + _( + "Vehicle-specific directory containing the intermediate\n" + "parameter files to be uploaded to the flight controller" + ), + _( + "Select the vehicle-specific configuration directory containing the\n" + "intermediate parameter files to be uploaded to the flight controller" + ) + if destroy_parent_on_open + else "", + False, + ) self.local_filesystem = local_filesystem self.destroy_parent_on_open = destroy_parent_on_open @@ -168,9 +180,13 @@ def on_select_directory(self): # Call the base class method to open the directory selection dialog if super().on_select_directory(): if "vehicle_templates" in self.directory and not self.local_filesystem.allow_editing_template_files: - messagebox.showerror(_("Invalid Vehicle Directory Selected"), - _("Please do not edit the files provided 'vehicle_templates' directory\n" - "as those are used as a template for new vehicles")) + messagebox.showerror( + _("Invalid Vehicle Directory Selected"), + _( + "Please do not edit the files provided 'vehicle_templates' directory\n" + "as those are used as a template for new vehicles" + ), + ) return self.local_filesystem.vehicle_dir = self.directory @@ -207,12 +223,14 @@ class VehicleDirectorySelectionWindow(BaseWindow): configuration directory based on an existing template or using an existing vehicle configuration directory. """ + def __init__(self, local_filesystem: LocalFilesystem, fc_connected: bool = False): super().__init__() self.local_filesystem = local_filesystem - self.root.title(_("Amilcar Lucas's - ArduPilot methodic configurator ") + VERSION + \ - _(" - Select vehicle configuration directory")) - self.root.geometry("800x625") # Set the window size + self.root.title( + _("Amilcar Lucas's - ArduPilot methodic configurator ") + VERSION + _(" - Select vehicle configuration directory") + ) + self.root.geometry("800x625") # Set the window size self.use_fc_params = tk.BooleanVar(value=False) self.configuration_template = None # will be set to a string if a template was used @@ -221,14 +239,15 @@ def __init__(self, local_filesystem: LocalFilesystem, fc_connected: bool = False introduction_text = _("No intermediate parameter files found\nin current working directory.") else: introduction_text = _("No intermediate parameter files found\nin the --vehicle-dir specified directory.") - introduction_label = ttk.Label(self.main_frame, anchor=tk.CENTER, justify=tk.CENTER, - text=introduction_text + _("\nChoose one of the following three options:")) + introduction_label = ttk.Label( + self.main_frame, + anchor=tk.CENTER, + justify=tk.CENTER, + text=introduction_text + _("\nChoose one of the following three options:"), + ) introduction_label.pack(expand=False, fill=tk.X, padx=6, pady=6) template_dir, new_base_dir, vehicle_dir = LocalFilesystem.get_recently_used_dirs() - self.create_option1_widgets(template_dir, - new_base_dir, - _("MyVehicleName"), - fc_connected) + self.create_option1_widgets(template_dir, new_base_dir, _("MyVehicleName"), fc_connected) self.create_option2_widgets(vehicle_dir) self.create_option3_widgets(vehicle_dir) @@ -238,73 +257,104 @@ def __init__(self, local_filesystem: LocalFilesystem, fc_connected: bool = False def close_and_quit(self): sys_exit(0) - def create_option1_widgets(self, initial_template_dir: str, initial_base_dir: str, - initial_new_dir: str, fc_connected: bool): + def create_option1_widgets( + self, initial_template_dir: str, initial_base_dir: str, initial_new_dir: str, fc_connected: bool + ): # Option 1 - Create a new vehicle configuration directory based on an existing template option1_label = ttk.Label(text=_("New"), style="Bold.TLabel") option1_label_frame = ttk.LabelFrame(self.main_frame, labelwidget=option1_label, borderwidth=2, relief="solid") option1_label_frame.pack(expand=True, fill=tk.X, padx=6, pady=6) - template_dir_edit_tooltip = _("Existing vehicle template directory containing the intermediate\n" \ - "parameter files to be copied to the new vehicle configuration directory") - template_dir_btn_tooltip = _("Select the existing vehicle template directory containing the intermediate\n" \ - "parameter files to be copied to the new vehicle configuration directory") - self.template_dir = DirectorySelectionWidgets(self, option1_label_frame, initial_template_dir, - _("Source Template directory:"), - False, - template_dir_edit_tooltip, - template_dir_btn_tooltip, - True) + template_dir_edit_tooltip = _( + "Existing vehicle template directory containing the intermediate\n" + "parameter files to be copied to the new vehicle configuration directory" + ) + template_dir_btn_tooltip = _( + "Select the existing vehicle template directory containing the intermediate\n" + "parameter files to be copied to the new vehicle configuration directory" + ) + self.template_dir = DirectorySelectionWidgets( + self, + option1_label_frame, + initial_template_dir, + _("Source Template directory:"), + False, + template_dir_edit_tooltip, + template_dir_btn_tooltip, + True, + ) self.template_dir.container_frame.pack(expand=False, fill=tk.X, padx=3, pady=5, anchor=tk.NW) - use_fc_params_checkbox = ttk.Checkbutton(option1_label_frame, variable=self.use_fc_params, - text=_("Use parameter values from connected FC, not from template files")) + use_fc_params_checkbox = ttk.Checkbutton( + option1_label_frame, + variable=self.use_fc_params, + text=_("Use parameter values from connected FC, not from template files"), + ) use_fc_params_checkbox.pack(anchor=tk.NW) - show_tooltip(use_fc_params_checkbox, - _("Use the parameter values from the connected flight controller instead of the\n" \ - "template files when creating a new vehicle configuration directory from a template.\n" \ - "This option is only available when a flight controller is connected")) + show_tooltip( + use_fc_params_checkbox, + _( + "Use the parameter values from the connected flight controller instead of the\n" + "template files when creating a new vehicle configuration directory from a template.\n" + "This option is only available when a flight controller is connected" + ), + ) if not fc_connected: self.use_fc_params.set(False) use_fc_params_checkbox.config(state=tk.DISABLED) new_base_dir_edit_tooltip = _("Existing directory where the new vehicle configuration directory will be created") new_base_dir_btn_tooltip = _("Select the directory where the new vehicle configuration directory will be created") - self.new_base_dir = DirectorySelectionWidgets(self, option1_label_frame, initial_base_dir, - _("Destination base directory:"), - False, - new_base_dir_edit_tooltip, - new_base_dir_btn_tooltip, - False) + self.new_base_dir = DirectorySelectionWidgets( + self, + option1_label_frame, + initial_base_dir, + _("Destination base directory:"), + False, + new_base_dir_edit_tooltip, + new_base_dir_btn_tooltip, + False, + ) self.new_base_dir.container_frame.pack(expand=False, fill=tk.X, padx=3, pady=5, anchor=tk.NW) - new_dir_edit_tooltip = _("A new vehicle configuration directory with this name will be created at the " \ - "(destination) base directory") - self.new_dir = DirectoryNameWidgets(option1_label_frame, initial_new_dir, - _("Destination new vehicle name:"), - new_dir_edit_tooltip) + new_dir_edit_tooltip = _( + "A new vehicle configuration directory with this name will be created at the (destination) base directory" + ) + self.new_dir = DirectoryNameWidgets( + option1_label_frame, initial_new_dir, _("Destination new vehicle name:"), new_dir_edit_tooltip + ) self.new_dir.container_frame.pack(expand=False, fill=tk.X, padx=3, pady=5, anchor=tk.NW) - create_vehicle_directory_from_template_button = ttk.Button(option1_label_frame, - text=_("Create vehicle configuration directory from " - "template"), - command=self.create_new_vehicle_from_template) + create_vehicle_directory_from_template_button = ttk.Button( + option1_label_frame, + text=_("Create vehicle configuration directory from template"), + command=self.create_new_vehicle_from_template, + ) create_vehicle_directory_from_template_button.pack(expand=False, fill=tk.X, padx=20, pady=5, anchor=tk.CENTER) - show_tooltip(create_vehicle_directory_from_template_button, - _("Create a new vehicle configuration directory on the (destination) base directory,\n" - "copy the template files from the (source) template directory to it and\n" - "load the newly created files into the application")) + show_tooltip( + create_vehicle_directory_from_template_button, + _( + "Create a new vehicle configuration directory on the (destination) base directory,\n" + "copy the template files from the (source) template directory to it and\n" + "load the newly created files into the application" + ), + ) def create_option2_widgets(self, initial_dir: str): # Option 2 - Use an existing vehicle configuration directory option2_label = ttk.Label(text=_("Open"), style="Bold.TLabel") option2_label_frame = ttk.LabelFrame(self.main_frame, labelwidget=option2_label, borderwidth=2, relief="solid") option2_label_frame.pack(expand=True, fill=tk.X, padx=6, pady=6) - option2_label = ttk.Label(option2_label_frame, anchor=tk.CENTER, justify=tk.CENTER, - text=_("Use an existing vehicle configuration directory with\n" \ - "intermediate parameter files, apm.pdef.xml and vehicle_components.json")) + option2_label = ttk.Label( + option2_label_frame, + anchor=tk.CENTER, + justify=tk.CENTER, + text=_( + "Use an existing vehicle configuration directory with\n" + "intermediate parameter files, apm.pdef.xml and vehicle_components.json" + ), + ) option2_label.pack(expand=False, fill=tk.X, padx=6) - self.connection_selection_widgets = VehicleDirectorySelectionWidgets(self, option2_label_frame, - self.local_filesystem, - initial_dir, - destroy_parent_on_open=True) + self.connection_selection_widgets = VehicleDirectorySelectionWidgets( + self, option2_label_frame, self.local_filesystem, initial_dir, destroy_parent_on_open=True + ) self.connection_selection_widgets.container_frame.pack(expand=True, fill=tk.X, padx=3, pady=5, anchor=tk.NW) def create_option3_widgets(self, last_vehicle_dir: str): @@ -313,25 +363,33 @@ def create_option3_widgets(self, last_vehicle_dir: str): option3_label_frame = ttk.LabelFrame(self.main_frame, labelwidget=option3_label, borderwidth=2, relief="solid") option3_label_frame.pack(expand=True, fill=tk.X, padx=6, pady=6) - last_dir = DirectorySelectionWidgets(self, option3_label_frame, last_vehicle_dir if last_vehicle_dir else '', - _("Last used vehicle configuration directory:"), - False, - _("Last used vehicle configuration directory"), - "", - False) + last_dir = DirectorySelectionWidgets( + self, + option3_label_frame, + last_vehicle_dir if last_vehicle_dir else "", + _("Last used vehicle configuration directory:"), + False, + _("Last used vehicle configuration directory"), + "", + False, + ) last_dir.container_frame.pack(expand=False, fill=tk.X, padx=3, pady=5, anchor=tk.NW) # Check if there is a last used vehicle configuration directory - button_state = tk.NORMAL if last_vehicle_dir and self.local_filesystem.directory_exists(last_vehicle_dir) else \ - tk.DISABLED - open_last_vehicle_directory_button = ttk.Button(option3_label_frame, - text=_("Open Last Used Vehicle Configuration Directory"), - command=lambda last_vehicle_dir=last_vehicle_dir: \ - self.open_last_vehicle_directory(last_vehicle_dir), - state=button_state) + button_state = ( + tk.NORMAL if last_vehicle_dir and self.local_filesystem.directory_exists(last_vehicle_dir) else tk.DISABLED + ) + open_last_vehicle_directory_button = ttk.Button( + option3_label_frame, + text=_("Open Last Used Vehicle Configuration Directory"), + command=lambda last_vehicle_dir=last_vehicle_dir: self.open_last_vehicle_directory(last_vehicle_dir), + state=button_state, + ) open_last_vehicle_directory_button.pack(expand=False, fill=tk.X, padx=20, pady=5, anchor=tk.CENTER) - show_tooltip(open_last_vehicle_directory_button, - _("Directly open the last used vehicle configuration directory for configuring and tuning the vehicle")) + show_tooltip( + open_last_vehicle_directory_button, + _("Directly open the last used vehicle configuration directory for configuring and tuning the vehicle"), + ) def create_new_vehicle_from_template(self): # Get the selected template directory and new vehicle configuration directory name @@ -404,9 +462,11 @@ def open_last_vehicle_directory(self, last_vehicle_dir: str): show_no_param_files_error(last_vehicle_dir) else: # If no last opened directory is found, display a message to the user - messagebox.showerror(_("No Last Vehicle Directory Found"), - _("No last opened vehicle configuration directory was found.\n" \ - "Please select a directory manually.")) + messagebox.showerror( + _("No Last Vehicle Directory Found"), + _("No last opened vehicle configuration directory was found.\nPlease select a directory manually."), + ) + def argument_parser(): """ @@ -417,19 +477,29 @@ def argument_parser(): Returns: argparse.Namespace: An object containing the parsed arguments. """ - parser = ArgumentParser(description=_('This main is for testing and development only. ' - 'Usually, the VehicleDirectorySelectionWindow is called from another script')) + parser = ArgumentParser( + description=_( + "This main is for testing and development only. " + "Usually, the VehicleDirectorySelectionWindow is called from another script" + ) + ) parser = LocalFilesystem.add_argparse_arguments(parser) return add_common_arguments_and_parse(parser) +# pylint: disable=duplicate-code def main(): args = argument_parser() - logging_basicConfig(level=logging_getLevelName(args.loglevel), format='%(asctime)s - %(levelname)s - %(message)s') + logging_basicConfig(level=logging_getLevelName(args.loglevel), format="%(asctime)s - %(levelname)s - %(message)s") - logging_warning(_("This main is for testing and development only, usually the VehicleDirectorySelectionWindow is" - " called from another script")) + logging_warning( + _( + "This main is for testing and development only, usually the VehicleDirectorySelectionWindow is" + " called from another script" + ) + ) + # pylint: enable=duplicate-code local_filesystem = LocalFilesystem(args.vehicle_dir, args.vehicle_type, None, args.allow_editing_template_files) diff --git a/MethodicConfigurator/frontend_tkinter_entry_dynamic.py b/MethodicConfigurator/frontend_tkinter_entry_dynamic.py index 8173aab..835b0e1 100644 --- a/MethodicConfigurator/frontend_tkinter_entry_dynamic.py +++ b/MethodicConfigurator/frontend_tkinter_entry_dynamic.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator https://code.activestate.com/recipes/580770-combobox-autocomplete/ @@ -8,16 +8,13 @@ SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' - - -from tkinter import StringVar, Entry, Listbox -from tkinter.constants import END, HORIZONTAL, N, S, E, W, VERTICAL, SINGLE +""" import tkinter as tk -from tkinter import ttk +from tkinter import Entry, Listbox, StringVar, ttk +from tkinter.constants import END, HORIZONTAL, SINGLE, VERTICAL, E, N, S, W -from MethodicConfigurator.internationalization import _ +from MethodicConfigurator import _ def autoscroll(sbar, first, last): @@ -34,8 +31,20 @@ class EntryWithDynamicalyFilteredListbox(Entry): # pylint: disable=too-many-anc """ Entry with dynamicaly filtered ListBox to emulate an inteligent combobox widget """ - def __init__(self, master, list_of_items=None, custom_filter_function=None, listbox_width=None, listbox_height=12, # pylint: disable=too-many-arguments - ignorecase_match=False, startswith_match=True, vscrollbar=True, hscrollbar=True, **kwargs): + + def __init__( # pylint: disable=too-many-arguments + self, + master, + list_of_items=None, + custom_filter_function=None, + listbox_width=None, + listbox_height=12, + ignorecase_match=False, + startswith_match=True, + vscrollbar=True, + hscrollbar=True, + **kwargs, + ): if list_of_items is None: raise ValueError(_("List_of_items can't be 'None'")) self._list_of_items = list_of_items @@ -58,14 +67,14 @@ def __init__(self, master, list_of_items=None, custom_filter_function=None, list Entry.__init__(self, master, **kwargs) - self._trace_id = self._entry_var.trace_add('write', self._on_change_entry_var) + self._trace_id = self._entry_var.trace_add("write", self._on_change_entry_var) self._listbox = None self.bind("", self._previous) self.bind("", self._next) - self.bind('', self._next) - self.bind('', self._previous) + self.bind("", self._next) + self.bind("", self._previous) self.bind("", self.update_entry_from_listbox) self.bind("", lambda event: self.unpost_listbox()) @@ -80,10 +89,9 @@ def default_filter_function(self, entry_data): return [item for item in self._list_of_items if entry_data in item] def _on_change_entry_var(self, _name, _index, _mode): - entry_data = self._entry_var.get() - if entry_data == '': + if entry_data == "": self.unpost_listbox() self.focus() else: @@ -107,39 +115,40 @@ def _on_change_entry_var(self, _name, _index, _mode): def _build_listbox(self, values): listbox_frame = ttk.Frame(self.master) - self._listbox = Listbox(listbox_frame, background="white", selectmode=SINGLE, activestyle="none", - exportselection=False) - self._listbox.grid(row=0, column=0,sticky = N+E+W+S) + self._listbox = Listbox( + listbox_frame, background="white", selectmode=SINGLE, activestyle="none", exportselection=False + ) + self._listbox.grid(row=0, column=0, sticky=N + E + W + S) self._listbox.bind("", self.update_entry_from_listbox) self._listbox.bind("", self.update_entry_from_listbox) self._listbox.bind("", lambda event: self.unpost_listbox()) - self._listbox.bind('', self._next) - self._listbox.bind('', self._previous) + self._listbox.bind("", self._next) + self._listbox.bind("", self._previous) if self._use_vscrollbar: - vbar = ttk.Scrollbar(listbox_frame, orient=VERTICAL, command= self._listbox.yview) - vbar.grid(row=0, column=1, sticky=N+S) + vbar = ttk.Scrollbar(listbox_frame, orient=VERTICAL, command=self._listbox.yview) + vbar.grid(row=0, column=1, sticky=N + S) - self._listbox.configure(yscrollcommand= lambda first, last: autoscroll(vbar, first, last)) + self._listbox.configure(yscrollcommand=lambda first, last: autoscroll(vbar, first, last)) if self._use_hscrollbar: - hbar = ttk.Scrollbar(listbox_frame, orient=HORIZONTAL, command= self._listbox.xview) - hbar.grid(row=1, column=0, sticky=E+W) + hbar = ttk.Scrollbar(listbox_frame, orient=HORIZONTAL, command=self._listbox.xview) + hbar.grid(row=1, column=0, sticky=E + W) - self._listbox.configure(xscrollcommand= lambda first, last: autoscroll(hbar, first, last)) + self._listbox.configure(xscrollcommand=lambda first, last: autoscroll(hbar, first, last)) - listbox_frame.grid_columnconfigure(0, weight= 1) - listbox_frame.grid_rowconfigure(0, weight= 1) + listbox_frame.grid_columnconfigure(0, weight=1) + listbox_frame.grid_rowconfigure(0, weight=1) x = -self.cget("borderwidth") - self.cget("highlightthickness") - y = self.winfo_height()-self.cget("borderwidth") - self.cget("highlightthickness") + y = self.winfo_height() - self.cget("borderwidth") - self.cget("highlightthickness") if self._listbox_width: width = self._listbox_width else: - width=self.winfo_width() + width = self.winfo_width() listbox_frame.place(in_=self, x=x, y=y, width=width) @@ -154,7 +163,7 @@ def post_listbox(self): return entry_data = self._entry_var.get() - if entry_data == '': + if entry_data == "": return values = self.filter_function(entry_data) @@ -181,7 +190,7 @@ def set_value(self, text, close_dialog=False): def _set_var(self, text): self._entry_var.trace_remove("write", self._trace_id) self._entry_var.set(text) - self._trace_id = self._entry_var.trace_add('write', self._on_change_entry_var) + self._trace_id = self._entry_var.trace_add("write", self._on_change_entry_var) def update_entry_from_listbox(self, _event): if self._listbox is not None: @@ -204,7 +213,7 @@ def _previous(self, _event): if self._listbox is not None: current_selection = self._listbox.curselection() - if len(current_selection)==0: + if len(current_selection) == 0: self._listbox.selection_set(0) self._listbox.activate(0) else: @@ -224,9 +233,8 @@ def _previous(self, _event): def _next(self, _event): if self._listbox is not None: - current_selection = self._listbox.curselection() - if len(current_selection)==0: + if len(current_selection) == 0: self._listbox.selection_set(0) self._listbox.activate(0) else: @@ -236,50 +244,126 @@ def _next(self, _event): if index == self._listbox.size() - 1: index = 0 else: - index +=1 + index += 1 self._listbox.see(index) self._listbox.selection_set(index) self._listbox.activate(index) return "break" -if __name__ == '__main__': - def main(): +if __name__ == "__main__": + + def main(): list_of_items = [ - "Cordell Cannata", "Lacey Naples", "Zachery Manigault", "Regan Brunt", - "Mario Hilgefort", "Austin Phong", "Moises Saum", "Willy Neill", - "Rosendo Sokoloff", "Salley Christenberry", "Toby Schneller", - "Angel Buchwald", "Nestor Criger", "Arie Jozwiak", "Nita Montelongo", - "Clemencia Okane", "Alison Scaggs", "Von Petrella", "Glennie Gurley", - "Jamar Callender", "Titus Wenrich", "Chadwick Liedtke", "Sharlene Yochum", - "Leonida Mutchler", "Duane Pickett", "Morton Brackins", "Ervin Trundy", - "Antony Orwig", "Audrea Yutzy", "Michal Hepp", "Annelle Hoadley", - "Hank Wyman", "Mika Fernandez", "Elisa Legendre", "Sade Nicolson", - "Jessie Yi", "Forrest Mooneyhan", "Alvin Widell", "Lizette Ruppe", - "Marguerita Pilarski", "Merna Argento", "Jess Daquila", "Breann Bevans", - "Melvin Guidry", "Jacelyn Vanleer", "Jerome Riendeau", "Iraida Nyquist", - "Micah Glantz", "Dorene Waldrip", "Fidel Garey", "Vertie Deady", - "Rosalinda Odegaard", "Chong Hayner", "Candida Palazzolo", "Bennie Faison", - "Nova Bunkley", "Francis Buckwalter", "Georgianne Espinal", "Karleen Dockins", - "Hertha Lucus", "Ike Alberty", "Deangelo Revelle", "Juli Gallup", - "Wendie Eisner", "Khalilah Travers", "Rex Outman", "Anabel King", - "Lorelei Tardiff", "Pablo Berkey", "Mariel Tutino", "Leigh Marciano", - "Ok Nadeau", "Zachary Antrim", "Chun Matthew", "Golden Keniston", - "Anthony Johson", "Rossana Ahlstrom", "Amado Schluter", "Delila Lovelady", - "Josef Belle", "Leif Negrete", "Alec Doss", "Darryl Stryker", - "Michael Cagley", "Sabina Alejo", "Delana Mewborn", "Aurelio Crouch", - "Ashlie Shulman", "Danielle Conlan", "Randal Donnell", "Rheba Anzalone", - "Lilian Truax", "Weston Quarterman", "Britt Brunt", "Leonie Corbett", - "Monika Gamet", "Ingeborg Bello", "Angelique Zhang", "Santiago Thibeau", - "Eliseo Helmuth" + "Cordell Cannata", + "Lacey Naples", + "Zachery Manigault", + "Regan Brunt", + "Mario Hilgefort", + "Austin Phong", + "Moises Saum", + "Willy Neill", + "Rosendo Sokoloff", + "Salley Christenberry", + "Toby Schneller", + "Angel Buchwald", + "Nestor Criger", + "Arie Jozwiak", + "Nita Montelongo", + "Clemencia Okane", + "Alison Scaggs", + "Von Petrella", + "Glennie Gurley", + "Jamar Callender", + "Titus Wenrich", + "Chadwick Liedtke", + "Sharlene Yochum", + "Leonida Mutchler", + "Duane Pickett", + "Morton Brackins", + "Ervin Trundy", + "Antony Orwig", + "Audrea Yutzy", + "Michal Hepp", + "Annelle Hoadley", + "Hank Wyman", + "Mika Fernandez", + "Elisa Legendre", + "Sade Nicolson", + "Jessie Yi", + "Forrest Mooneyhan", + "Alvin Widell", + "Lizette Ruppe", + "Marguerita Pilarski", + "Merna Argento", + "Jess Daquila", + "Breann Bevans", + "Melvin Guidry", + "Jacelyn Vanleer", + "Jerome Riendeau", + "Iraida Nyquist", + "Micah Glantz", + "Dorene Waldrip", + "Fidel Garey", + "Vertie Deady", + "Rosalinda Odegaard", + "Chong Hayner", + "Candida Palazzolo", + "Bennie Faison", + "Nova Bunkley", + "Francis Buckwalter", + "Georgianne Espinal", + "Karleen Dockins", + "Hertha Lucus", + "Ike Alberty", + "Deangelo Revelle", + "Juli Gallup", + "Wendie Eisner", + "Khalilah Travers", + "Rex Outman", + "Anabel King", + "Lorelei Tardiff", + "Pablo Berkey", + "Mariel Tutino", + "Leigh Marciano", + "Ok Nadeau", + "Zachary Antrim", + "Chun Matthew", + "Golden Keniston", + "Anthony Johson", + "Rossana Ahlstrom", + "Amado Schluter", + "Delila Lovelady", + "Josef Belle", + "Leif Negrete", + "Alec Doss", + "Darryl Stryker", + "Michael Cagley", + "Sabina Alejo", + "Delana Mewborn", + "Aurelio Crouch", + "Ashlie Shulman", + "Danielle Conlan", + "Randal Donnell", + "Rheba Anzalone", + "Lilian Truax", + "Weston Quarterman", + "Britt Brunt", + "Leonie Corbett", + "Monika Gamet", + "Ingeborg Bello", + "Angelique Zhang", + "Santiago Thibeau", + "Eliseo Helmuth", ] root = tk.Tk() root.geometry("300x300") - combobox_autocomplete = EntryWithDynamicalyFilteredListbox(root, list_of_items=list_of_items, - ignorecase_match=True, startswith_match=False) + combobox_autocomplete = EntryWithDynamicalyFilteredListbox( + root, list_of_items=list_of_items, ignorecase_match=True, startswith_match=False + ) combobox_autocomplete.pack() diff --git a/MethodicConfigurator/frontend_tkinter_flightcontroller_info.py b/MethodicConfigurator/frontend_tkinter_flightcontroller_info.py index ff9dc09..e9a7d5a 100644 --- a/MethodicConfigurator/frontend_tkinter_flightcontroller_info.py +++ b/MethodicConfigurator/frontend_tkinter_flightcontroller_info.py @@ -1,28 +1,24 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' - -#from logging import debug as logging_debug -from logging import info as logging_info +""" +# from logging import debug as logging_debug import tkinter as tk +from logging import info as logging_info from tkinter import ttk from MethodicConfigurator.backend_flightcontroller import FlightController -#from MethodicConfigurator.backend_flightcontroller_info import BackendFlightcontrollerInfo - -#from MethodicConfigurator.frontend_tkinter_base import show_tooltip -from MethodicConfigurator.frontend_tkinter_base import ProgressWindow -from MethodicConfigurator.frontend_tkinter_base import BaseWindow - -from MethodicConfigurator.internationalization import _ +# from MethodicConfigurator.backend_flightcontroller_info import BackendFlightcontrollerInfo +# from MethodicConfigurator.frontend_tkinter_base import show_tooltip +from MethodicConfigurator.frontend_tkinter_base import BaseWindow, ProgressWindow +from MethodicConfigurator import _ from MethodicConfigurator.version import VERSION @@ -30,6 +26,7 @@ class FlightControllerInfoWindow(BaseWindow): """ Display flight controller hardware, firmware and parameter information """ + def __init__(self, flight_controller: FlightController): super().__init__() self.root.title(_("ArduPilot methodic configurator ") + VERSION + _(" - Flight Controller Info")) @@ -68,14 +65,16 @@ def __init__(self, flight_controller: FlightController): logging_info(_("Flight Controller USB vendor ID: %s"), flight_controller.info.vendor) logging_info(_("Flight Controller USB product ID: %s"), flight_controller.info.product) - self.root.after(50, self.download_flight_controller_parameters()) # 50 milliseconds + self.root.after(50, self.download_flight_controller_parameters()) # 50 milliseconds self.root.mainloop() def download_flight_controller_parameters(self): - param_download_progress_window = ProgressWindow(self.root, _("Downloading FC parameters"), - _("Downloaded {} of {} parameters")) + param_download_progress_window = ProgressWindow( + self.root, _("Downloading FC parameters"), _("Downloaded {} of {} parameters") + ) self.flight_controller.fc_parameters, self.param_default_values = self.flight_controller.download_params( - param_download_progress_window.update_progress_bar) + param_download_progress_window.update_progress_bar + ) param_download_progress_window.destroy() # for the case that '--device test' and there is no real FC connected self.root.destroy() diff --git a/MethodicConfigurator/frontend_tkinter_pair_tuple_combobox.py b/MethodicConfigurator/frontend_tkinter_pair_tuple_combobox.py index 1dbe3bd..4e1783c 100644 --- a/MethodicConfigurator/frontend_tkinter_pair_tuple_combobox.py +++ b/MethodicConfigurator/frontend_tkinter_pair_tuple_combobox.py @@ -1,37 +1,28 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' - -from sys import exit as sys_exit +""" +import tkinter as tk +import tkinter.font as tkfont from argparse import ArgumentParser - from logging import basicConfig as logging_basicConfig -from logging import getLevelName as logging_getLevelName +from logging import critical as logging_critical from logging import debug as logging_debug +from logging import getLevelName as logging_getLevelName from logging import warning as logging_warning -from logging import critical as logging_critical - -import tkinter as tk -from tkinter import ttk -from tkinter import Toplevel -from tkinter import Label -import tkinter.font as tkfont - from platform import system as platform_system +from sys import exit as sys_exit +from tkinter import Label, Toplevel, ttk from MethodicConfigurator.common_arguments import add_common_arguments_and_parse - -from MethodicConfigurator.frontend_tkinter_base import update_combobox_width -from MethodicConfigurator.frontend_tkinter_base import get_widget_font - -from MethodicConfigurator.internationalization import _ +from MethodicConfigurator.frontend_tkinter_base import get_widget_font, update_combobox_width +from MethodicConfigurator import _ # https://dev.to/geraldew/python-tkinter-an-exercise-in-wrapping-the-combobox-ndb @@ -41,13 +32,14 @@ class PairTupleCombobox(ttk.Combobox): # pylint: disable=too-many-ancestors This widget processes the list of tuples to separate keys and values for display purposes and allows for the selection of a tuple based on its key. """ + def __init__(self, container, list_pair_tuple, selected_element, cb_name, *args, **kwargs): super().__init__(container, *args, **kwargs) self.cb_name = cb_name self.list_keys = [] self.list_shows = [] self.set_entries_tupple(list_pair_tuple, selected_element) - self.bind('', self.on_combo_configure, add='+') + self.bind("", self.on_combo_configure, add="+") def set_entries_tupple(self, list_pair_tuple, selected_element): if isinstance(list_pair_tuple, list): @@ -61,19 +53,21 @@ def set_entries_tupple(self, list_pair_tuple, selected_element): else: logging_critical(_("list_pair_tuple must be a tuple or a dictionary, not %s"), type(list_pair_tuple)) sys_exit(1) - self['values'] = tuple(self.list_shows) + self["values"] = tuple(self.list_shows) if selected_element: try: default_key_index = self.list_keys.index(selected_element) self.current(default_key_index) except IndexError: - logging_critical(_("%s combobox selected string '%s' not in list %s"), - self.cb_name, selected_element, self.list_keys) + logging_critical( + _("%s combobox selected string '%s' not in list %s"), self.cb_name, selected_element, self.list_keys + ) sys_exit(1) except ValueError: - logging_critical(_("%s combobox selected string '%s' not in list %s"), - self.cb_name, selected_element, self.list_keys) + logging_critical( + _("%s combobox selected string '%s' not in list %s"), self.cb_name, selected_element, self.list_keys + ) sys_exit(1) update_combobox_width(self) else: @@ -91,21 +85,21 @@ def on_combo_configure(self, event): combo = event.widget style = ttk.Style() # check if the combobox already has the "postoffset" property - current_combo_style = combo.cget('style') or "TCombobox" - if len(style.lookup(current_combo_style, 'postoffset')) > 0: + current_combo_style = combo.cget("style") or "TCombobox" + if len(style.lookup(current_combo_style, "postoffset")) > 0: return - combo_values = combo.cget('values') + combo_values = combo.cget("values") if len(combo_values) == 0: return longest_value = max(combo_values, key=len) - #font = tkfont.nametofont(combo.cget('font')) + # font = tkfont.nametofont(combo.cget('font')) font = tkfont.nametofont("TkDefaultFont") width = font.measure(longest_value + "0000") - event.width if width < 0: # no need to make the popdown smaller return # create an unique style name using widget's id - unique_name=f'Combobox{combo.winfo_id()}' + unique_name = f"Combobox{combo.winfo_id()}" # the new style must inherit from current widget style (unless it's our custom style!) if unique_name in current_combo_style: style_name = current_combo_style @@ -138,31 +132,32 @@ class PairTupleComboboxTooltip(PairTupleCombobox): # pylint: disable=too-many-a a) An item is selected from the dropdown b) The dropdown is closed (either by selection or pressing Esc) """ + def __init__(self, container, list_pair_tuple, selected_element, cb_name, *args, **kwargs): super().__init__(container, list_pair_tuple, selected_element, cb_name, *args, **kwargs) self.tooltip = None # Bind events related to the dropdown - pd = self.tk.call('ttk::combobox::PopdownWindow', self) - lb = pd + '.f.l' - self._bind(('bind', lb),"", self.on_key_release, None) - self._bind(('bind', lb),"", self.on_motion, None) - self._bind(('bind', lb),"", self.on_escape_press, None) + pd = self.tk.call("ttk::combobox::PopdownWindow", self) + lb = pd + ".f.l" + self._bind(("bind", lb), "", self.on_key_release, None) + self._bind(("bind", lb), "", self.on_motion, None) + self._bind(("bind", lb), "", self.on_escape_press, None) self.bind("<>", self.on_combobox_selected, None) def on_key_release(self, _event): - """ Get the keyboard highlighted index and create a tooltip for it """ - pd = self.tk.call('ttk::combobox::PopdownWindow', self) - lb = pd + '.f.l' - if self.tk.call(lb, 'curselection'): - highlighted_index = int(self.tk.call(lb, 'curselection')[0]) + """Get the keyboard highlighted index and create a tooltip for it""" + pd = self.tk.call("ttk::combobox::PopdownWindow", self) + lb = pd + ".f.l" + if self.tk.call(lb, "curselection"): + highlighted_index = int(self.tk.call(lb, "curselection")[0]) self.create_tooltip_from_index(highlighted_index) def on_motion(self, event): - """ Get the mouse highlighted index and create a tooltip for it """ - pd = self.tk.call('ttk::combobox::PopdownWindow', self) - lb = pd + '.f.l' - index = self.tk.call(lb, 'index', f'@{event.x},{event.y}') + """Get the mouse highlighted index and create a tooltip for it""" + pd = self.tk.call("ttk::combobox::PopdownWindow", self) + lb = pd + ".f.l" + index = self.tk.call(lb, "index", f"@{event.x},{event.y}") self.create_tooltip_from_index(int(index)) def create_tooltip_from_index(self, index): @@ -193,7 +188,7 @@ def on_escape_press(self, _event): self.destroy_tooltip() def destroy_tooltip(self): - if hasattr(self, 'tooltip') and self.tooltip and self.tooltip.winfo_exists(): + if hasattr(self, "tooltip") and self.tooltip and self.tooltip.winfo_exists(): self.tooltip.destroy() self.tooltip = None @@ -207,18 +202,23 @@ def argument_parser(): Returns: argparse.Namespace: An object containing the parsed arguments. """ - parser = ArgumentParser(description=_('A GUI for testing the PairTupleCombobox. ' - 'Not to be used directly, but through the main ArduPilot methodic configurator script.')) + parser = ArgumentParser( + description=_( + "A GUI for testing the PairTupleCombobox. " + "Not to be used directly, but through the main ArduPilot methodic configurator script." + ) + ) return add_common_arguments_and_parse(parser) def main(): argsp = argument_parser() - logging_basicConfig(level=logging_getLevelName(argsp.loglevel), format='%(asctime)s - %(levelname)s - %(message)s') + logging_basicConfig(level=logging_getLevelName(argsp.loglevel), format="%(asctime)s - %(levelname)s - %(message)s") - logging_warning(_("This main is for testing and development only, usually the PairTupleCombobox is called from " - "another script")) + logging_warning( + _("This main is for testing and development only, usually the PairTupleCombobox is called from another script") + ) root = tk.Tk() root.title("Random String Selector") @@ -227,16 +227,18 @@ def main(): # Generate 20 random strings between 4 and 70 characters import random # pylint: disable=import-outside-toplevel import string # pylint: disable=import-outside-toplevel - random_strings = [''.join(random.choices(string.ascii_letters + string.digits, k=random.randint(4, 70))) \ - for _ in range(20)] + + random_strings = [ + "".join(random.choices(string.ascii_letters + string.digits, k=random.randint(4, 70))) for _ in range(20) + ] # Create the PairTupleCombobox2 instance tuple_pairs = [(str(i), random_string) for i, random_string in enumerate(random_strings)] combobox = PairTupleCombobox(root, tuple_pairs, None, "Random Strings") font = get_widget_font(combobox) - font['size'] -= 2 if platform_system() == 'Windows' else 1 - combobox.config(state='readonly', width=9, font=(font['family'], font['size'])) + font["size"] -= 2 if platform_system() == "Windows" else 1 + combobox.config(state="readonly", width=9, font=(font["family"], font["size"])) # Pack the combobox into the main window combobox.pack(pady=10, padx=10) @@ -244,7 +246,7 @@ def main(): # Set the initial value combobox.set(str(1)) - tuple_pairs = [('1', 'One'), ('2', 'Two'), ('3', 'Test')] + tuple_pairs = [("1", "One"), ("2", "Two"), ("3", "Test")] # Create a PairTupleComboboxTooltip instance tooltip_combobox = PairTupleComboboxTooltip(root, tuple_pairs, None, "Tooltip Items") diff --git a/MethodicConfigurator/frontend_tkinter_parameter_editor.py b/MethodicConfigurator/frontend_tkinter_parameter_editor.py index 912dc0c..3325d58 100644 --- a/MethodicConfigurator/frontend_tkinter_parameter_editor.py +++ b/MethodicConfigurator/frontend_tkinter_parameter_editor.py @@ -1,60 +1,46 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' - -from argparse import ArgumentParser +""" import tkinter as tk -from tkinter import messagebox -from tkinter import ttk -from tkinter import filedialog - +from argparse import ArgumentParser from logging import basicConfig as logging_basicConfig +from logging import error as logging_error from logging import getLevelName as logging_getLevelName -#from logging import debug as logging_debug + +# from logging import debug as logging_debug from logging import info as logging_info from logging import warning as logging_warning -from logging import error as logging_error -#from logging import critical as logging_critical - -from typing import List -from typing import Tuple +from tkinter import filedialog, messagebox, ttk +# from logging import critical as logging_critical +from typing import List, Tuple from webbrowser import open as webbrowser_open # to open the blog post documentation from MethodicConfigurator.annotate_params import Par - -from MethodicConfigurator.common_arguments import add_common_arguments_and_parse - -from MethodicConfigurator.backend_filesystem import LocalFilesystem -from MethodicConfigurator.backend_filesystem import is_within_tolerance - +from MethodicConfigurator.backend_filesystem import LocalFilesystem, is_within_tolerance from MethodicConfigurator.backend_filesystem_program_settings import ProgramSettings - from MethodicConfigurator.backend_flightcontroller import FlightController - -from MethodicConfigurator.frontend_tkinter_base import show_tooltip -from MethodicConfigurator.frontend_tkinter_base import AutoResizeCombobox -from MethodicConfigurator.frontend_tkinter_base import ProgressWindow -from MethodicConfigurator.frontend_tkinter_base import BaseWindow -from MethodicConfigurator.frontend_tkinter_base import RichText -from MethodicConfigurator.frontend_tkinter_base import get_widget_font -from MethodicConfigurator.frontend_tkinter_base import UsagePopupWindow - +from MethodicConfigurator.common_arguments import add_common_arguments_and_parse +from MethodicConfigurator.frontend_tkinter_base import ( + AutoResizeCombobox, + BaseWindow, + ProgressWindow, + RichText, + UsagePopupWindow, + get_widget_font, + show_tooltip, +) from MethodicConfigurator.frontend_tkinter_directory_selection import VehicleDirectorySelectionWidgets - from MethodicConfigurator.frontend_tkinter_parameter_editor_table import ParameterEditorTable - -from MethodicConfigurator.internationalization import _ - +from MethodicConfigurator import _ from MethodicConfigurator.tempcal_imu import IMUfit - from MethodicConfigurator.version import VERSION @@ -67,6 +53,7 @@ class DocumentationFrame: # pylint: disable=too-few-public-methods the documentation links based on the current file and provides functionality to open these links in a web browser. """ + def __init__(self, root: tk.Tk, local_filesystem, current_file: str): self.root = root self.local_filesystem = local_filesystem @@ -84,11 +71,15 @@ def __create_documentation_frame(self): documentation_grid.pack(fill="both", expand=True) descriptive_texts = [_("Forum Blog:"), _("Wiki:"), _("External tool:"), _("Mandatory:")] - descriptive_tooltips = [_("ArduPilot's forum Methodic configuration Blog post relevant for the current file"), - _("ArduPilot's wiki page relevant for the current file"), - _("External tool or documentation relevant for the current file"), - _("Mandatory level of the current file,\n 100% you MUST use this file to configure the " - "vehicle,\n 0% you can ignore this file if it does not apply to your vehicle")] + descriptive_tooltips = [ + _("ArduPilot's forum Methodic configuration Blog post relevant for the current file"), + _("ArduPilot's wiki page relevant for the current file"), + _("External tool or documentation relevant for the current file"), + _( + "Mandatory level of the current file,\n 100% you MUST use this file to configure the " + "vehicle,\n 0% you can ignore this file if it does not apply to your vehicle" + ), + ] for i, text in enumerate(descriptive_texts): # Create labels for the first column with static descriptive text label = ttk.Label(documentation_grid, text=text) @@ -111,16 +102,16 @@ def update_documentation_labels(self, current_file: str): frame_title = _("Documentation") self.documentation_frame.config(text=frame_title) - blog_text, blog_url = self.local_filesystem.get_documentation_text_and_url(current_file, 'blog') - self.__update_documentation_label(_('Forum Blog:'), blog_text, blog_url) - wiki_text, wiki_url = self.local_filesystem.get_documentation_text_and_url(current_file, 'wiki') - self.__update_documentation_label(_('Wiki:'), wiki_text, wiki_url) - external_tool_text, external_tool_url = self.local_filesystem.get_documentation_text_and_url(current_file, - 'external_tool') - self.__update_documentation_label(_('External tool:'), external_tool_text, external_tool_url) - mandatory_text, mandatory_url = self.local_filesystem.get_documentation_text_and_url(current_file, - 'mandatory') - self.__update_documentation_label(_('Mandatory:'), mandatory_text, mandatory_url, False) + blog_text, blog_url = self.local_filesystem.get_documentation_text_and_url(current_file, "blog") + self.__update_documentation_label(_("Forum Blog:"), blog_text, blog_url) + wiki_text, wiki_url = self.local_filesystem.get_documentation_text_and_url(current_file, "wiki") + self.__update_documentation_label(_("Wiki:"), wiki_text, wiki_url) + external_tool_text, external_tool_url = self.local_filesystem.get_documentation_text_and_url( + current_file, "external_tool" + ) + self.__update_documentation_label(_("External tool:"), external_tool_text, external_tool_url) + mandatory_text, mandatory_url = self.local_filesystem.get_documentation_text_and_url(current_file, "mandatory") + self.__update_documentation_label(_("Mandatory:"), mandatory_text, mandatory_url, False) def __update_documentation_label(self, label_key, text, url, url_expected=True): label = self.documentation_labels[label_key] @@ -145,10 +136,12 @@ def show_about_window(root, _version: str): # pylint: disable=too-many-locals main_frame.pack(expand=True, fill=tk.BOTH) # Add the "About" message - about_message = _("ArduPilot Methodic Configurator Version: {_version}\n\n" \ - "A clear configuration sequence for ArduPilot vehicles.\n\n" \ - "Copyright © 2024 Amilcar do Carmo Lucas and ArduPilot.org\n\n" \ - "Licensed under the GNU General Public License v3.0") + about_message = _( + "ArduPilot Methodic Configurator Version: {_version}\n\n" + "A clear configuration sequence for ArduPilot vehicles.\n\n" + "Copyright © 2024 Amilcar do Carmo Lucas and ArduPilot.org\n\n" + "Licensed under the GNU General Public License v3.0" + ) about_label = ttk.Label(main_frame, text=about_message.format(**locals()), wraplength=450) about_label.grid(column=0, row=0, padx=10, pady=10, columnspan=5) # Span across all columns @@ -159,35 +152,47 @@ def show_about_window(root, _version: str): # pylint: disable=too-many-locals usage_popup_label.pack(side=tk.TOP, anchor=tk.W) component_editor_var = tk.BooleanVar(value=ProgramSettings.display_usage_popup("component_editor")) - component_editor_checkbox = ttk.Checkbutton(usage_popup_frame, text=_("Component editor window"), - variable=component_editor_var, - command=lambda: ProgramSettings.set_display_usage_popup("component_editor", - component_editor_var.get())) + component_editor_checkbox = ttk.Checkbutton( + usage_popup_frame, + text=_("Component editor window"), + variable=component_editor_var, + command=lambda: ProgramSettings.set_display_usage_popup("component_editor", component_editor_var.get()), + ) component_editor_checkbox.pack(side=tk.TOP, anchor=tk.W) parameter_editor_var = tk.BooleanVar(value=ProgramSettings.display_usage_popup("parameter_editor")) - parameter_editor_checkbox = ttk.Checkbutton(usage_popup_frame, text=_("Parameter file editor and uploader window"), - variable=parameter_editor_var, - command=lambda: ProgramSettings.set_display_usage_popup("parameter_editor", - parameter_editor_var.get())) + parameter_editor_checkbox = ttk.Checkbutton( + usage_popup_frame, + text=_("Parameter file editor and uploader window"), + variable=parameter_editor_var, + command=lambda: ProgramSettings.set_display_usage_popup("parameter_editor", parameter_editor_var.get()), + ) parameter_editor_checkbox.pack(side=tk.TOP, anchor=tk.W) # Create buttons for each action - user_manual_button = ttk.Button(main_frame, text=_("User Manual"), - command=lambda: webbrowser_open( - "https://github.com/ArduPilot/MethodicConfigurator/blob/master/USERMANUAL.md")) - support_forum_button = ttk.Button(main_frame, text=_("Support Forum"), - command=lambda: webbrowser_open( - "http://discuss.ardupilot.org/t/new-ardupilot-methodic-configurator-gui/115038/1")) - report_bug_button = ttk.Button(main_frame, text=_("Report a Bug"), - command=lambda: webbrowser_open( - "https://github.com/ArduPilot/MethodicConfigurator/issues/new")) - licenses_button = ttk.Button(main_frame, text=_("Licenses"), - command=lambda: webbrowser_open( - "https://github.com/ArduPilot/MethodicConfigurator/blob/master/credits/CREDITS.md")) - source_button = ttk.Button(main_frame, text=_("Source Code"), - command=lambda: webbrowser_open( - "https://github.com/ArduPilot/MethodicConfigurator")) + user_manual_button = ttk.Button( + main_frame, + text=_("User Manual"), + command=lambda: webbrowser_open("https://github.com/ArduPilot/MethodicConfigurator/blob/master/USERMANUAL.md"), + ) + support_forum_button = ttk.Button( + main_frame, + text=_("Support Forum"), + command=lambda: webbrowser_open("http://discuss.ardupilot.org/t/new-ardupilot-methodic-configurator-gui/115038/1"), + ) + report_bug_button = ttk.Button( + main_frame, + text=_("Report a Bug"), + command=lambda: webbrowser_open("https://github.com/ArduPilot/MethodicConfigurator/issues/new"), + ) + licenses_button = ttk.Button( + main_frame, + text=_("Licenses"), + command=lambda: webbrowser_open("https://github.com/ArduPilot/MethodicConfigurator/blob/master/credits/CREDITS.md"), + ) + source_button = ttk.Button( + main_frame, text=_("Source Code"), command=lambda: webbrowser_open("https://github.com/ArduPilot/MethodicConfigurator") + ) # Place buttons using grid for equal spacing and better control over layout user_manual_button.grid(column=0, row=2, padx=10, pady=10) @@ -207,8 +212,8 @@ class ParameterEditorWindow(BaseWindow): # pylint: disable=too-many-instance-at and provides functionalities for displaying and interacting with drone parameters, documentation, and flight controller connection settings. """ - def __init__(self, current_file: str, flight_controller: FlightController, - local_filesystem: LocalFilesystem): + + def __init__(self, current_file: str, flight_controller: FlightController, local_filesystem: LocalFilesystem): super().__init__() self.current_file = current_file self.flight_controller = flight_controller @@ -224,21 +229,22 @@ def __init__(self, current_file: str, flight_controller: FlightController, self.tempcal_imu_progress_window = None self.file_upload_progress_window = None - self.root.title(_("Amilcar Lucas's - ArduPilot methodic configurator ") + VERSION + \ - _(" - Parameter file editor and uploader")) - self.root.geometry("990x550") # Set the window width + self.root.title( + _("Amilcar Lucas's - ArduPilot methodic configurator ") + VERSION + _(" - Parameter file editor and uploader") + ) + self.root.geometry("990x550") # Set the window width # Bind the close_connection_and_quit function to the window close event self.root.protocol("WM_DELETE_WINDOW", self.close_connection_and_quit) style = ttk.Style() - style.map('readonly.TCombobox', fieldbackground=[('readonly', 'white')]) - style.map('readonly.TCombobox', selectbackground=[('readonly', 'white')]) - style.map('readonly.TCombobox', selectforeground=[('readonly', 'black')]) - style.map('default_v.TCombobox', fieldbackground=[('readonly', 'light blue')]) - style.map('default_v.TCombobox', selectbackground=[('readonly', 'light blue')]) - style.map('default_v.TCombobox', selectforeground=[('readonly', 'black')]) - style.configure('default_v.TEntry', fieldbackground="light blue") + style.map("readonly.TCombobox", fieldbackground=[("readonly", "white")]) + style.map("readonly.TCombobox", selectbackground=[("readonly", "white")]) + style.map("readonly.TCombobox", selectforeground=[("readonly", "black")]) + style.map("default_v.TCombobox", fieldbackground=[("readonly", "light blue")]) + style.map("default_v.TCombobox", selectbackground=[("readonly", "light blue")]) + style.map("default_v.TCombobox", selectforeground=[("readonly", "black")]) + style.configure("default_v.TEntry", fieldbackground="light blue") self.__create_conf_widgets(VERSION) @@ -257,16 +263,16 @@ def __init__(self, current_file: str, flight_controller: FlightController, def __create_conf_widgets(self, version: str): config_frame = ttk.Frame(self.main_frame) - config_frame.pack(side=tk.TOP, fill="x", expand=False, pady=(4, 0)) # Pack the frame at the top of the window + config_frame.pack(side=tk.TOP, fill="x", expand=False, pady=(4, 0)) # Pack the frame at the top of the window config_subframe = ttk.Frame(config_frame) - config_subframe.pack(side=tk.LEFT, fill="x", expand=True, anchor=tk.NW) # Pack the frame at the top of the window + config_subframe.pack(side=tk.LEFT, fill="x", expand=True, anchor=tk.NW) # Pack the frame at the top of the window # Create a new frame inside the config_subframe for the intermediate parameter file directory selection labels # and directory selection button - directory_selection_frame = VehicleDirectorySelectionWidgets(self, config_subframe, self.local_filesystem, - self.local_filesystem.vehicle_dir, - destroy_parent_on_open=False) + directory_selection_frame = VehicleDirectorySelectionWidgets( + self, config_subframe, self.local_filesystem, self.local_filesystem.vehicle_dir, destroy_parent_on_open=False + ) directory_selection_frame.container_frame.pack(side=tk.LEFT, fill="x", expand=False, padx=(4, 6)) # Create a new frame inside the config_subframe for the intermediate parameter file selection label and combobox @@ -275,21 +281,27 @@ def __create_conf_widgets(self, version: str): # Create a label for the Combobox file_selection_label = ttk.Label(file_selection_frame, text=_("Current intermediate parameter file:")) - file_selection_label.pack(side=tk.TOP, anchor=tk.NW) # Add the label to the top of the file_selection_frame + file_selection_label.pack(side=tk.TOP, anchor=tk.NW) # Add the label to the top of the file_selection_frame # Create Combobox for intermediate parameter file selection - self.file_selection_combobox = AutoResizeCombobox(file_selection_frame, - list(self.local_filesystem.file_parameters.keys()), - self.current_file, - _("Select the intermediate parameter file from the list of available" - " files in the selected vehicle directory\nIt will automatically " - "advance to the next file once the current file is uploaded to the " - "fight controller"), - state='readonly', width=45, style='readonly.TCombobox') + self.file_selection_combobox = AutoResizeCombobox( + file_selection_frame, + list(self.local_filesystem.file_parameters.keys()), + self.current_file, + _( + "Select the intermediate parameter file from the list of available" + " files in the selected vehicle directory\nIt will automatically " + "advance to the next file once the current file is uploaded to the " + "fight controller" + ), + state="readonly", + width=45, + style="readonly.TCombobox", + ) self.file_selection_combobox.bind("<>", self.on_param_file_combobox_change) self.file_selection_combobox.pack(side=tk.TOP, anchor=tk.NW, pady=(4, 0)) - self.legend_frame(config_subframe, get_widget_font(file_selection_label)['family']) + self.legend_frame(config_subframe, get_widget_font(file_selection_label)["family"]) image_label = BaseWindow.put_image_in_label(config_frame, LocalFilesystem.application_logo_filepath()) image_label.pack(side=tk.RIGHT, anchor=tk.NE, padx=(4, 4), pady=(4, 0)) @@ -298,8 +310,8 @@ def __create_conf_widgets(self, version: str): def legend_frame(self, config_subframe: ttk.Frame, font_family: str): style = ttk.Style() - style.configure('Legend.TLabelframe', font=(font_family, 9)) - legend_frame = ttk.LabelFrame(config_subframe, text=_("Legend"), style='Legend.TLabelframe') + style.configure("Legend.TLabelframe", font=(font_family, 9)) + legend_frame = ttk.LabelFrame(config_subframe, text=_("Legend"), style="Legend.TLabelframe") legend_left = ttk.Frame(legend_frame) legend_left.pack(side=tk.LEFT, anchor=tk.NW) show_tooltip(legend_frame, _("the meaning of the text background colors")) @@ -319,7 +331,7 @@ def legend_frame(self, config_subframe: ttk.Frame, font_family: str): na_label = ttk.Label(legend_right, text=_("Not available"), background="orange", font=font) na_label.pack(side=tk.TOP, anchor=tk.NW) ne_label = ttk.Label(legend_right, text=_("Not editable"), font=font) - ne_label.configure(state='disabled') + ne_label.configure(state="disabled") ne_label.pack(side=tk.TOP, anchor=tk.NW) legend_frame.pack(side=tk.LEFT, fill="x", expand=False, padx=(2, 2)) @@ -341,44 +353,69 @@ def __create_parameter_area_widgets(self): checkboxes_frame.pack(side=tk.LEFT, padx=(8, 8)) # Create a checkbox for toggling parameter display - only_changed_checkbox = ttk.Checkbutton(checkboxes_frame, text=_("See only changed parameters"), - variable=self.show_only_differences, - command=self.on_show_only_changed_checkbox_change) + only_changed_checkbox = ttk.Checkbutton( + checkboxes_frame, + text=_("See only changed parameters"), + variable=self.show_only_differences, + command=self.on_show_only_changed_checkbox_change, + ) only_changed_checkbox.pack(side=tk.TOP, anchor=tk.NW) - show_tooltip(only_changed_checkbox, _("Toggle to show only parameters that will change if/when uploaded to the flight " - "controller")) - - annotate_params_checkbox = ttk.Checkbutton(checkboxes_frame, text=_("Annotate docs into .param files"), - state='normal' if self.local_filesystem.doc_dict else 'disabled', - variable=self.annotate_params_into_files) + show_tooltip( + only_changed_checkbox, + _("Toggle to show only parameters that will change if/when uploaded to the flight controller"), + ) + + annotate_params_checkbox = ttk.Checkbutton( + checkboxes_frame, + text=_("Annotate docs into .param files"), + state="normal" if self.local_filesystem.doc_dict else "disabled", + variable=self.annotate_params_into_files, + ) annotate_params_checkbox.pack(side=tk.TOP, anchor=tk.NW) - show_tooltip(annotate_params_checkbox, _("Annotate ArduPilot parameter documentation metadata into the intermediate " - "parameter files\n" - "The files will be bigger, but all the existing parameter documentation will be included inside")) + show_tooltip( + annotate_params_checkbox, + _( + "Annotate ArduPilot parameter documentation metadata into the intermediate parameter files\n" + "The files will be bigger, but all the existing parameter documentation will be included inside" + ), + ) # Create upload button - upload_selected_button = ttk.Button(buttons_frame, text=_("Upload selected params to FC, " - "and advance to next param file"), - command=self.on_upload_selected_click) - upload_selected_button.configure(state='normal' if self.flight_controller.master else 'disabled') - upload_selected_button.pack(side=tk.LEFT, padx=(8, 8)) # Add padding on both sides of the upload selected button - show_tooltip(upload_selected_button, _("Upload selected parameters to the flight controller and advance to the next " - "intermediate parameter file\nIf changes have been made to the current file it will ask if you want " - "to save them\nIt will reset the FC if necessary, re-download all parameters and validate their value")) + upload_selected_button = ttk.Button( + buttons_frame, + text=_("Upload selected params to FC, and advance to next param file"), + command=self.on_upload_selected_click, + ) + upload_selected_button.configure(state="normal" if self.flight_controller.master else "disabled") + upload_selected_button.pack(side=tk.LEFT, padx=(8, 8)) # Add padding on both sides of the upload selected button + show_tooltip( + upload_selected_button, + _( + "Upload selected parameters to the flight controller and advance to the next " + "intermediate parameter file\nIf changes have been made to the current file it will ask if you want " + "to save them\nIt will reset the FC if necessary, re-download all parameters and validate their value" + ), + ) # Create skip button skip_button = ttk.Button(buttons_frame, text=_("Skip parameter file"), command=self.on_skip_click) - skip_button.pack(side=tk.RIGHT, padx=(8, 8)) # Add right padding to the skip button - show_tooltip(skip_button, _("Skip to the next intermediate parameter file without uploading any changes to the flight " - "controller\nIf changes have been made to the current file it will ask if you want to save them")) + skip_button.pack(side=tk.RIGHT, padx=(8, 8)) # Add right padding to the skip button + show_tooltip( + skip_button, + _( + "Skip to the next intermediate parameter file without uploading any changes to the flight " + "controller\nIf changes have been made to the current file it will ask if you want to save them" + ), + ) @staticmethod def __display_usage_popup_window(parent: tk.Tk): usage_popup_window = BaseWindow(parent) style = ttk.Style() - instructions_text = RichText(usage_popup_window.main_frame, wrap=tk.WORD, height=5, bd=0, - background=style.lookup("TLabel", "background")) + instructions_text = RichText( + usage_popup_window.main_frame, wrap=tk.WORD, height=5, bd=0, background=style.lookup("TLabel", "background") + ) instructions_text.insert(tk.END, _("1. Read ")) instructions_text.insert(tk.END, _("all"), "bold") instructions_text.insert(tk.END, _(" the documentation on top of the parameter table\n")) @@ -398,28 +435,51 @@ def __display_usage_popup_window(parent: tk.Tk): instructions_text.insert(tk.END, _("5. Repeat from the top until the program automatically closes")) instructions_text.config(state=tk.DISABLED) - UsagePopupWindow.display(parent, usage_popup_window, _("How to use the parameter file editor and uploader window"), - "parameter_editor", "690x200", instructions_text) - - def __do_tempcal_imu(self, selected_file:str): - tempcal_imu_result_param_filename, tempcal_imu_result_param_fullpath = \ - self.local_filesystem.tempcal_imu_result_param_tuple() + UsagePopupWindow.display( + parent, + usage_popup_window, + _("How to use the parameter file editor and uploader window"), + "parameter_editor", + "690x200", + instructions_text, + ) + + def __do_tempcal_imu(self, selected_file: str): + tempcal_imu_result_param_filename, tempcal_imu_result_param_fullpath = ( + self.local_filesystem.tempcal_imu_result_param_tuple() + ) if selected_file == tempcal_imu_result_param_filename: - msg = _("If you proceed the {tempcal_imu_result_param_filename}\n" - "will be overwritten with the new calibration results.\n" - "Do you want to provide a .bin log file and\n" - "run the IMU temperature calibration using it?") + msg = _( + "If you proceed the {tempcal_imu_result_param_filename}\n" + "will be overwritten with the new calibration results.\n" + "Do you want to provide a .bin log file and\n" + "run the IMU temperature calibration using it?" + ) if messagebox.askyesno(_("IMU temperature calibration"), msg.format(**locals())): # file selection dialog to select the *.bin file to be used in the IMUfit temperature calibration filename = filedialog.askopenfilename(filetypes=[(_("ArduPilot binary log files"), ["*.bin", "*.BIN"])]) if filename: - messagebox.showwarning(_("IMU temperature calibration"), _("Please wait, this can take a really long time " - "and\nthe GUI will be unresponsive until it finishes.")) - self.tempcal_imu_progress_window = ProgressWindow(self.main_frame, _("Reading IMU calibration messages"), - _("Please wait, this can take a long time")) + messagebox.showwarning( + _("IMU temperature calibration"), + _( + "Please wait, this can take a really long time " + "and\nthe GUI will be unresponsive until it finishes." + ), + ) + self.tempcal_imu_progress_window = ProgressWindow( + self.main_frame, _("Reading IMU calibration messages"), _("Please wait, this can take a long time") + ) # Pass the selected filename to the IMUfit class - IMUfit(filename, tempcal_imu_result_param_fullpath, False, False, False, False, - self.local_filesystem.vehicle_dir, self.tempcal_imu_progress_window.update_progress_bar_300_pct) + IMUfit( + filename, + tempcal_imu_result_param_fullpath, + False, + False, + False, + False, + self.local_filesystem.vehicle_dir, + self.tempcal_imu_progress_window.update_progress_bar_300_pct, + ) self.tempcal_imu_progress_window.destroy() try: self.local_filesystem.file_parameters = self.local_filesystem.read_params_from_files() @@ -431,13 +491,18 @@ def __do_tempcal_imu(self, selected_file:str): def __should_copy_fc_values_to_file(self, selected_file: str): auto_changed_by = self.local_filesystem.auto_changed_by(selected_file) if auto_changed_by and self.flight_controller.fc_parameters: - msg = _("This configuration step should be performed outside this tool by\n" - "{auto_changed_by}\n" - "and that should have changed the parameters on the FC.\n\n" - "Should the FC values now be copied to the {selected_file} file?") + msg = _( + "This configuration step should be performed outside this tool by\n" + "{auto_changed_by}\n" + "and that should have changed the parameters on the FC.\n\n" + "Should the FC values now be copied to the {selected_file} file?" + ) if messagebox.askyesno(_("Update file with values from FC?"), msg.format(**locals())): - relevant_fc_params = {key: value for key, value in self.flight_controller.fc_parameters.items() \ - if key in self.local_filesystem.file_parameters[selected_file]} + relevant_fc_params = { + key: value + for key, value in self.flight_controller.fc_parameters.items() + if key in self.local_filesystem.file_parameters[selected_file] + } params_copied = self.local_filesystem.copy_fc_values_to_file(selected_file, relevant_fc_params) if params_copied: self.parameter_editor_table.set_at_least_one_param_edited(True) @@ -471,10 +536,12 @@ def __should_upload_file_to_fc(self, selected_file: str): if self.flight_controller.master: msg = _("Should the {local_filename} file be uploaded to the flight controller as {remote_filename}?") if messagebox.askyesno(_("Upload file to FC"), msg.format(**locals())): - self.file_upload_progress_window = ProgressWindow(self.main_frame, _("Uploading file"), - _("Uploaded {} of {} %")) - if not self.flight_controller.upload_file(local_filename, remote_filename, - self.file_upload_progress_window.update_progress_bar): + self.file_upload_progress_window = ProgressWindow( + self.main_frame, _("Uploading file"), _("Uploaded {} of {} %") + ) + if not self.flight_controller.upload_file( + local_filename, remote_filename, self.file_upload_progress_window.update_progress_bar + ): error_msg = _("Failed to upload {local_filename} to {remote_filename}, please upload it manually") messagebox.showerror(_("Upload failed"), error_msg.format(**locals())) self.file_upload_progress_window.destroy() @@ -483,7 +550,7 @@ def __should_upload_file_to_fc(self, selected_file: str): messagebox.showwarning(_("Will not upload any file"), _("No flight controller connection")) def on_param_file_combobox_change(self, _event, forced: bool = False): - if not self.file_selection_combobox['values']: + if not self.file_selection_combobox["values"]: return self.parameter_editor_table.generate_edit_widgets_focus_out() selected_file = self.file_selection_combobox.get() @@ -503,21 +570,23 @@ def on_param_file_combobox_change(self, _event, forced: bool = False): def download_flight_controller_parameters(self, redownload: bool = False): operation_string = _("Re-downloading FC parameters") if redownload else _("Downloading FC parameters") - self.param_download_progress_window = ProgressWindow(self.main_frame, operation_string, - _("Downloaded {} of {} parameters")) + self.param_download_progress_window = ProgressWindow( + self.main_frame, operation_string, _("Downloaded {} of {} parameters") + ) # Download all parameters from the flight controller self.flight_controller.fc_parameters, param_default_values = self.flight_controller.download_params( - self.param_download_progress_window.update_progress_bar) + self.param_download_progress_window.update_progress_bar + ) if param_default_values: self.local_filesystem.write_param_default_values_to_file(param_default_values) self.param_download_progress_window.destroy() # for the case that '--device test' and there is no real FC connected if not redownload: - self.on_param_file_combobox_change(None, True) # the initial param read will trigger a table update + self.on_param_file_combobox_change(None, True) # the initial param read will trigger a table update def repopulate_parameter_table(self, selected_file): if not selected_file: return # no file was yet selected, so skip it - if hasattr(self.flight_controller, 'fc_parameters') and self.flight_controller.fc_parameters: + if hasattr(self.flight_controller, "fc_parameters") and self.flight_controller.fc_parameters: fc_parameters = self.flight_controller.fc_parameters else: fc_parameters = {} @@ -540,25 +609,34 @@ def upload_params_that_require_reset(self, selected_params: dict): for param_name, param in selected_params.items(): try: logging_info(_("Parameter %s set to %f"), param_name, param.value) - if param_name not in self.flight_controller.fc_parameters or \ - not is_within_tolerance(self.flight_controller.fc_parameters[param_name], param.value): + if param_name not in self.flight_controller.fc_parameters or not is_within_tolerance( + self.flight_controller.fc_parameters[param_name], param.value + ): param_metadata = self.local_filesystem.doc_dict.get(param_name, None) - if param_metadata and param_metadata.get('RebootRequired', False): + if param_metadata and param_metadata.get("RebootRequired", False): self.flight_controller.set_param(param_name, float(param.value)) self.at_least_one_changed_parameter_written = True if param_name in self.flight_controller.fc_parameters: - logging_info(_("Parameter %s changed from %f to %f, reset required"), param_name, - self.flight_controller.fc_parameters[param_name], param.value) + logging_info( + _("Parameter %s changed from %f to %f, reset required"), + param_name, + self.flight_controller.fc_parameters[param_name], + param.value, + ) else: logging_info(_("Parameter %s changed to %f, reset required"), param_name, param.value) fc_reset_required = True # Check if any of the selected parameters have a _TYPE, _EN, or _ENABLE suffix - elif param_name.endswith(('_TYPE', '_EN', '_ENABLE', 'SID_AXIS')): + elif param_name.endswith(("_TYPE", "_EN", "_ENABLE", "SID_AXIS")): self.flight_controller.set_param(param_name, float(param.value)) self.at_least_one_changed_parameter_written = True if param_name in self.flight_controller.fc_parameters: - logging_info(_("Parameter %s changed from %f to %f, possible reset required"), param_name, - self.flight_controller.fc_parameters[param_name], param.value) + logging_info( + _("Parameter %s changed from %f to %f, possible reset required"), + param_name, + self.flight_controller.fc_parameters[param_name], + param.value, + ) else: logging_info(_("Parameter %s changed to %f, possible reset required"), param_name, param.value) fc_reset_unsure.append(param_name) @@ -573,19 +651,21 @@ def __reset_and_reconnect(self, fc_reset_required, fc_reset_unsure): if not fc_reset_required: if fc_reset_unsure: # Ask the user if they want to reset the ArduPilot - _param_list_str = (', ').join(fc_reset_unsure) + _param_list_str = (", ").join(fc_reset_unsure) msg = _("{_param_list_str} parameter(s) potentially require a reset\nDo you want to reset the ArduPilot?") fc_reset_required = messagebox.askyesno(_("Possible reset required"), msg.format(**locals())) if fc_reset_required: - self.reset_progress_window = ProgressWindow(self.main_frame, _("Resetting Flight Controller"), - _("Waiting for {} of {} seconds")) - filesystem_boot_delay = self.local_filesystem.file_parameters[self.current_file].get('BRD_BOOT_DELAY', Par(0.0)) - flightcontroller_boot_delay = self.flight_controller.fc_parameters.get('BRD_BOOT_DELAY', 0) + self.reset_progress_window = ProgressWindow( + self.main_frame, _("Resetting Flight Controller"), _("Waiting for {} of {} seconds") + ) + filesystem_boot_delay = self.local_filesystem.file_parameters[self.current_file].get("BRD_BOOT_DELAY", Par(0.0)) + flightcontroller_boot_delay = self.flight_controller.fc_parameters.get("BRD_BOOT_DELAY", 0) extra_sleep_time = max(filesystem_boot_delay.value, flightcontroller_boot_delay) // 1000 + 1 # round up # Call reset_and_reconnect with a callback to update the reset progress bar and the progress message - error_message = self.flight_controller.reset_and_reconnect(self.reset_progress_window.update_progress_bar, None, - extra_sleep_time) + error_message = self.flight_controller.reset_and_reconnect( + self.reset_progress_window.update_progress_bar, None, extra_sleep_time + ) if error_message: logging_error(error_message) messagebox.showerror(_("ArduPilot methodic configurator"), error_message) @@ -597,11 +677,12 @@ def on_upload_selected_click(self): self.write_changes_to_intermediate_parameter_file() selected_params = self.parameter_editor_table.get_upload_selected_params(self.current_file) if selected_params: - if hasattr(self.flight_controller, 'fc_parameters') and self.flight_controller.fc_parameters: + if hasattr(self.flight_controller, "fc_parameters") and self.flight_controller.fc_parameters: self.upload_selected_params(selected_params) else: - logging_warning(_("No parameters were yet downloaded from the flight controller, " - "will not upload any parameter")) + logging_warning( + _("No parameters were yet downloaded from the flight controller, will not upload any parameter") + ) messagebox.showwarning(_("Will not upload any parameter"), _("No flight controller connection")) else: logging_warning(_("No parameter was selected for upload, will not upload any parameter")) @@ -620,8 +701,9 @@ def upload_selected_params(self, selected_params): try: self.flight_controller.set_param(param_name, param.value) logging_info(_("Parameter %s set to %f"), param_name, param.value) - if param_name not in self.flight_controller.fc_parameters or \ - not is_within_tolerance(self.flight_controller.fc_parameters[param_name], param.value): + if param_name not in self.flight_controller.fc_parameters or not is_within_tolerance( + self.flight_controller.fc_parameters[param_name], param.value + ): self.at_least_one_changed_parameter_written = True except ValueError as _e: error_msg = _("Failed to set parameter {param_name}: {_e}").format(**locals()) @@ -636,21 +718,32 @@ def upload_selected_params(self, selected_params): # Validate that the read parameters are the same as the ones in the current_file param_upload_error = [] for param_name, param in selected_params.items(): - if param_name in self.flight_controller.fc_parameters and \ - param is not None and \ - not is_within_tolerance(self.flight_controller.fc_parameters[param_name], float(param.value)): - logging_error(_("Parameter %s upload to the flight controller failed. Expected: %f, Actual: %f"), - param_name, param.value, self.flight_controller.fc_parameters[param_name]) + if ( + param_name in self.flight_controller.fc_parameters + and param is not None + and not is_within_tolerance(self.flight_controller.fc_parameters[param_name], float(param.value)) + ): + logging_error( + _("Parameter %s upload to the flight controller failed. Expected: %f, Actual: %f"), + param_name, + param.value, + self.flight_controller.fc_parameters[param_name], + ) param_upload_error.append(param_name) if param_name not in self.flight_controller.fc_parameters: - logging_error(_("Parameter %s upload to the flight controller failed. Expected: %f, Actual: N/A"), - param_name, param.value) + logging_error( + _("Parameter %s upload to the flight controller failed. Expected: %f, Actual: N/A"), + param_name, + param.value, + ) param_upload_error.append(param_name) if param_upload_error: - if messagebox.askretrycancel(_("Parameter upload error"), - _("Failed to upload the following parameters to the flight controller:\n") + - f"{(', ').join(param_upload_error)}"): + if messagebox.askretrycancel( + _("Parameter upload error"), + _("Failed to upload the following parameters to the flight controller:\n") + + f"{(', ').join(param_upload_error)}", + ): self.upload_selected_params(selected_params) else: logging_info(_("All parameters uploaded to the flight controller successfully")) @@ -686,47 +779,59 @@ def write_changes_to_intermediate_parameter_file(self): if self.parameter_editor_table.get_at_least_one_param_edited(): msg = _("Do you want to write the changes to the {self.current_file} file?") if messagebox.askyesno(_("One or more parameters have been edited"), msg.format(**locals())): - self.local_filesystem.export_to_param(self.local_filesystem.file_parameters[self.current_file], - self.current_file, annotate_doc=self.annotate_params_into_files.get()) + self.local_filesystem.export_to_param( + self.local_filesystem.file_parameters[self.current_file], + self.current_file, + annotate_doc=self.annotate_params_into_files.get(), + ) self.parameter_editor_table.set_at_least_one_param_edited(False) def write_summary_files(self): # pylint: disable=too-many-locals - if not hasattr(self.flight_controller, 'fc_parameters') or self.flight_controller.fc_parameters is None: + if not hasattr(self.flight_controller, "fc_parameters") or self.flight_controller.fc_parameters is None: return annotated_fc_parameters = self.local_filesystem.annotate_intermediate_comments_to_param_dict( - self.flight_controller.fc_parameters) - non_default__read_only_params, non_default__writable_calibrations, non_default__writable_non_calibrations = \ + self.flight_controller.fc_parameters + ) + non_default__read_only_params, non_default__writable_calibrations, non_default__writable_non_calibrations = ( self.local_filesystem.categorize_parameters(annotated_fc_parameters) + ) nr_total_params = len(annotated_fc_parameters) nr_non_default__read_only_params = len(non_default__read_only_params) nr_non_default__writable_calibrations = len(non_default__writable_calibrations) nr_non_default__writable_non_calibrations = len(non_default__writable_non_calibrations) - _nr_unchanged_params = nr_total_params - nr_non_default__read_only_params - \ - nr_non_default__writable_calibrations - nr_non_default__writable_non_calibrations + _nr_unchanged_params = ( + nr_total_params + - nr_non_default__read_only_params + - nr_non_default__writable_calibrations + - nr_non_default__writable_non_calibrations + ) # If there are no more files, present a summary message box - summary_message = _("Methodic configuration of {nr_total_params} parameters complete:\n\n" \ - "{_nr_unchanged_params} kept their default value\n\n" \ - "{nr_non_default__read_only_params} non-default read-only parameters - " \ - "ignore these, you can not change them\n\n" \ - "{nr_non_default__writable_calibrations} non-default writable sensor-calibrations - " \ - "non-reusable between vehicles\n\n" \ - "{nr_non_default__writable_non_calibrations} non-default writable non-sensor-calibrations - " \ - "these can be reused between similar vehicles") + summary_message = _( + "Methodic configuration of {nr_total_params} parameters complete:\n\n" + "{_nr_unchanged_params} kept their default value\n\n" + "{nr_non_default__read_only_params} non-default read-only parameters - " + "ignore these, you can not change them\n\n" + "{nr_non_default__writable_calibrations} non-default writable sensor-calibrations - " + "non-reusable between vehicles\n\n" + "{nr_non_default__writable_non_calibrations} non-default writable non-sensor-calibrations - " + "these can be reused between similar vehicles" + ) messagebox.showinfo(_("Last parameter file processed"), summary_message.format(**locals())) - wrote_complete = self.write_summary_file(annotated_fc_parameters, - "complete.param", False) - wrote_read_only = self.write_summary_file(non_default__read_only_params, - "non-default_read-only.param", False) - wrote_calibrations = self.write_summary_file(non_default__writable_calibrations, - "non-default_writable_calibrations.param", False) - wrote_non_calibrations = self.write_summary_file(non_default__writable_non_calibrations, - "non-default_writable_non-calibrations.param", False) + wrote_complete = self.write_summary_file(annotated_fc_parameters, "complete.param", False) + wrote_read_only = self.write_summary_file(non_default__read_only_params, "non-default_read-only.param", False) + wrote_calibrations = self.write_summary_file( + non_default__writable_calibrations, "non-default_writable_calibrations.param", False + ) + wrote_non_calibrations = self.write_summary_file( + non_default__writable_non_calibrations, "non-default_writable_non-calibrations.param", False + ) files_to_zip = [ (wrote_complete, "complete.param"), (wrote_read_only, "non-default_read-only.param"), (wrote_calibrations, "non-default_writable_calibrations.param"), - (wrote_non_calibrations, "non-default_writable_non-calibrations.param")] + (wrote_non_calibrations, "non-default_writable_non-calibrations.param"), + ] self.write_zip_file(files_to_zip) def write_summary_file(self, param_dict: dict, filename: str, annotate_doc: bool): @@ -748,16 +853,18 @@ def write_zip_file(self, files_to_zip: List[Tuple[bool, str]]): should_write_file = messagebox.askyesno(_("Overwrite existing file"), msg.format(zip_file_path)) if should_write_file: self.local_filesystem.zip_files(files_to_zip) - msg = _("All relevant files have been zipped into the \n" - "{zip_file_path} file.\n\nYou can now upload this file to the ArduPilot Methodic\n" - "Configuration Blog post on discuss.ardupilot.org.") + msg = _( + "All relevant files have been zipped into the \n" + "{zip_file_path} file.\n\nYou can now upload this file to the ArduPilot Methodic\n" + "Configuration Blog post on discuss.ardupilot.org." + ) messagebox.showinfo(_("Parameter files zipped"), msg.format(**locals())) return should_write_file def close_connection_and_quit(self): self.parameter_editor_table.generate_edit_widgets_focus_out() self.write_changes_to_intermediate_parameter_file() - self.root.quit() # Then stop the Tkinter event loop + self.root.quit() # Then stop the Tkinter event loop @staticmethod def add_argparse_arguments(parser): @@ -773,8 +880,12 @@ def argument_parser(): Returns: argparse.Namespace: An object containing the parsed arguments. """ - parser = ArgumentParser(description=_('A GUI for editing ArduPilot param files. ' - 'Not to be used directly, but through the main ArduPilot methodic configurator script.')) + parser = ArgumentParser( + description=_( + "A GUI for editing ArduPilot param files. " + "Not to be used directly, but through the main ArduPilot methodic configurator script." + ) + ) parser = FlightController.add_argparse_arguments(parser) parser = LocalFilesystem.add_argparse_arguments(parser) parser = ParameterEditorWindow.add_argparse_arguments(parser) @@ -784,8 +895,8 @@ def argument_parser(): if __name__ == "__main__": args = argument_parser() - logging_basicConfig(level=logging_getLevelName(args.loglevel), format='%(asctime)s - %(levelname)s - %(message)s') + logging_basicConfig(level=logging_getLevelName(args.loglevel), format="%(asctime)s - %(levelname)s - %(message)s") fc = FlightController(args.reboot_time) filesystem = LocalFilesystem(args.vehicle_dir, args.vehicle_type, None, args.allow_editing_template_files) - ParameterEditorWindow('04_board_orientation.param', fc, filesystem) + ParameterEditorWindow("04_board_orientation.param", fc, filesystem) diff --git a/MethodicConfigurator/frontend_tkinter_parameter_editor_table.py b/MethodicConfigurator/frontend_tkinter_parameter_editor_table.py index 4bd0564..3b1eaac 100644 --- a/MethodicConfigurator/frontend_tkinter_parameter_editor_table.py +++ b/MethodicConfigurator/frontend_tkinter_parameter_editor_table.py @@ -1,49 +1,39 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' - -from sys import exit as sys_exit +""" import tkinter as tk -from tkinter import messagebox -from tkinter import ttk +# from logging import warning as logging_warning +# from logging import error as logging_error +from logging import critical as logging_critical from logging import debug as logging_debug from logging import info as logging_info -#from logging import warning as logging_warning -#from logging import error as logging_error -from logging import critical as logging_critical - from platform import system as platform_system +from sys import exit as sys_exit +from tkinter import messagebox, ttk -#from MethodicConfigurator.backend_filesystem import LocalFilesystem -from MethodicConfigurator.backend_filesystem import is_within_tolerance - -#from MethodicConfigurator.backend_flightcontroller import FlightController - -from MethodicConfigurator.frontend_tkinter_base import show_tooltip -#from MethodicConfigurator.frontend_tkinter_base import AutoResizeCombobox -from MethodicConfigurator.frontend_tkinter_base import ScrollFrame -from MethodicConfigurator.frontend_tkinter_base import get_widget_font -from MethodicConfigurator.frontend_tkinter_base import BaseWindow +from MethodicConfigurator.annotate_params import Par -from MethodicConfigurator.frontend_tkinter_pair_tuple_combobox import PairTupleCombobox +# from MethodicConfigurator.backend_filesystem import LocalFilesystem +from MethodicConfigurator.backend_filesystem import is_within_tolerance +# from MethodicConfigurator.backend_flightcontroller import FlightController +# from MethodicConfigurator.frontend_tkinter_base import AutoResizeCombobox +from MethodicConfigurator.frontend_tkinter_base import BaseWindow, ScrollFrame, get_widget_font, show_tooltip from MethodicConfigurator.frontend_tkinter_entry_dynamic import EntryWithDynamicalyFilteredListbox - -from MethodicConfigurator.internationalization import _ - -from MethodicConfigurator.annotate_params import Par - +from MethodicConfigurator.frontend_tkinter_pair_tuple_combobox import PairTupleCombobox +from MethodicConfigurator import _ NEW_VALUE_WIDGET_WIDTH = 9 + class ParameterEditorTable(ScrollFrame): # pylint: disable=too-many-ancestors """ A class to manage and display the parameter editor table within the GUI. @@ -51,6 +41,7 @@ class ParameterEditorTable(ScrollFrame): # pylint: disable=too-many-ancestors This class inherits from ScrollFrame and is responsible for creating, managing, and updating the table that displays parameters for editing. """ + def __init__(self, root, local_filesystem, parameter_editor): super().__init__(root) self.root = root @@ -61,7 +52,7 @@ def __init__(self, root, local_filesystem, parameter_editor): self.at_least_one_param_edited = False style = ttk.Style() - style.configure('narrow.TButton', padding=0, width=4, border=(0, 0, 0, 0)) + style.configure("narrow.TButton", padding=0, width=4, border=(0, 0, 0, 0)) # Prepare a dictionary that maps variable names to their values # These variables are used by the forced_parameters and derived_parameters in configuration_steps_*.json files @@ -72,23 +63,24 @@ def __init__(self, root, local_filesystem, parameter_editor): def compute_forced_and_derived_parameters(self): if self.local_filesystem.configuration_steps: for filename, file_info in self.local_filesystem.configuration_steps.items(): - error_msg = self.local_filesystem.compute_parameters(filename, file_info, 'forced', self.variables) + error_msg = self.local_filesystem.compute_parameters(filename, file_info, "forced", self.variables) if error_msg: messagebox.showerror(_("Error in forced parameters"), error_msg) else: self.add_forced_or_derived_parameters(filename, self.local_filesystem.forced_parameters) - #error_msg = self.local_filesystem.compute_parameters(filename, file_info, 'derived', self.variables) - #if error_msg: + # error_msg = self.local_filesystem.compute_parameters(filename, file_info, 'derived', self.variables) + # if error_msg: # messagebox.showerror("Error in derived parameters", error_msg) def add_forced_or_derived_parameters(self, filename, new_parameters, fc_parameters=None): - ''' Add forced parameters not yet in the parameter list to the parameter list ''' + """Add forced parameters not yet in the parameter list to the parameter list""" if filename in new_parameters: for param_name, param in new_parameters[filename].items(): if filename not in self.local_filesystem.file_parameters: continue - if param_name not in self.local_filesystem.file_parameters[filename] and \ - (fc_parameters is None or param_name in fc_parameters): + if param_name not in self.local_filesystem.file_parameters[filename] and ( + fc_parameters is None or param_name in fc_parameters + ): self.local_filesystem.file_parameters[filename][param_name] = param def repopulate(self, selected_file: str, fc_parameters: dict, show_only_differences: bool): @@ -98,27 +90,29 @@ def repopulate(self, selected_file: str, fc_parameters: dict, show_only_differen # Create labels for table headers headers = [_("-/+"), _("Parameter"), _("Current Value"), _("New Value"), _("Unit"), _("Upload"), _("Change Reason")] - tooltips = [_("Delete or add a parameter"), - _("Parameter name must be ^[A-Z][A-Z_0-9]* and most 16 characters long"), - _("Current value on the flight controller "), - _("New value from the above selected intermediate parameter file"), - _("Parameter Unit"), - _("When selected, upload the new value to the flight controller"), - _("Reason why respective parameter changed")] + tooltips = [ + _("Delete or add a parameter"), + _("Parameter name must be ^[A-Z][A-Z_0-9]* and most 16 characters long"), + _("Current value on the flight controller "), + _("New value from the above selected intermediate parameter file"), + _("Parameter Unit"), + _("When selected, upload the new value to the flight controller"), + _("Reason why respective parameter changed"), + ] for i, header in enumerate(headers): label = ttk.Label(self.view_port, text=header) - label.grid(row=0, column=i, sticky="ew") # Use sticky="ew" to make the label stretch horizontally + label.grid(row=0, column=i, sticky="ew") # Use sticky="ew" to make the label stretch horizontally show_tooltip(label, tooltips[i]) self.upload_checkbutton_var = {} # re-compute derived parameters because the fc_parameters values might have changed if self.local_filesystem.configuration_steps and selected_file in self.local_filesystem.configuration_steps: - self.variables['fc_parameters'] = fc_parameters - error_msg = self.local_filesystem.compute_parameters(selected_file, - self.local_filesystem.configuration_steps[selected_file], - 'derived', self.variables) + self.variables["fc_parameters"] = fc_parameters + error_msg = self.local_filesystem.compute_parameters( + selected_file, self.local_filesystem.configuration_steps[selected_file], "derived", self.variables + ) if error_msg: messagebox.showerror(_("Error in derived parameters"), error_msg) else: @@ -129,10 +123,14 @@ def repopulate(self, selected_file: str, fc_parameters: dict, show_only_differen if show_only_differences: # recompute different_params because of renames and derived values changes - different_params = {param_name: file_value for param_name, file_value in - self.local_filesystem.file_parameters[selected_file].items() - if param_name not in fc_parameters or (param_name in fc_parameters and \ - not is_within_tolerance(fc_parameters[param_name], float(file_value.value)))} + different_params = { + param_name: file_value + for param_name, file_value in self.local_filesystem.file_parameters[selected_file].items() + if param_name not in fc_parameters + or ( + param_name in fc_parameters and not is_within_tolerance(fc_parameters[param_name], float(file_value.value)) + ) + } self.__update_table(different_params, fc_parameters) if not different_params: info_msg = _("No different parameters found in {selected_file}. Skipping...").format(**locals()) @@ -150,16 +148,16 @@ def rename_fc_connection(self, selected_file): if "rename_connection" in self.local_filesystem.configuration_steps[selected_file]: new_connection_prefix = self.local_filesystem.configuration_steps[selected_file]["rename_connection"] new_connection_prefix = eval(str(new_connection_prefix), {}, self.variables) # pylint: disable=eval-used - for param_name, _param_value in self.local_filesystem.file_parameters[selected_file].items(): + for param_name in self.local_filesystem.file_parameters[selected_file].keys(): new_prefix = new_connection_prefix old_prefix = param_name.split("_")[0] # Handle CAN parameter names peculiarities if new_connection_prefix[:-1] == "CAN" and "CAN_P" in param_name: - old_prefix = param_name.split("_")[0] + '_' + param_name.split("_")[1] + old_prefix = param_name.split("_")[0] + "_" + param_name.split("_")[1] new_prefix = "CAN_P" + new_connection_prefix[-1] if new_connection_prefix[:-1] == "CAN" and "CAN_D" in param_name: - old_prefix = param_name.split("_")[0] + '_' + param_name.split("_")[1] + old_prefix = param_name.split("_")[0] + "_" + param_name.split("_")[1] new_prefix = "CAN_D" + new_connection_prefix[-1] if new_connection_prefix[:-1] in old_prefix: @@ -175,11 +173,14 @@ def rename_fc_connection(self, selected_file): else: new_names.add(new_name) if new_name != old_name: - self.local_filesystem.file_parameters[selected_file][new_name] = \ - self.local_filesystem.file_parameters[selected_file].pop(old_name) + self.local_filesystem.file_parameters[selected_file][new_name] = self.local_filesystem.file_parameters[ + selected_file + ].pop(old_name) logging_info(_("Renaming parameter %s to %s"), old_name, new_name) - info_msg = _("The parameter '{old_name}' was renamed to '{new_name}'.\n" - "to obey the flight controller connection defined in the component editor window.") + info_msg = _( + "The parameter '{old_name}' was renamed to '{new_name}'.\n" + "to obey the flight controller connection defined in the component editor window." + ) messagebox.showinfo(_("Parameter Renamed"), info_msg.format(**locals())) def __update_table(self, params, fc_parameters): @@ -187,8 +188,11 @@ def __update_table(self, params, fc_parameters): for i, (param_name, param) in enumerate(params.items(), 1): param_metadata = self.local_filesystem.doc_dict.get(param_name, None) param_default = self.local_filesystem.param_default_dict.get(param_name, None) - doc_tooltip = param_metadata.get('doc_tooltip') if param_metadata else \ - _("No documentation available in apm.pdef.xml for this parameter") + doc_tooltip = ( + param_metadata.get("doc_tooltip") + if param_metadata + else _("No documentation available in apm.pdef.xml for this parameter") + ) column = [] column.append(self.__create_delete_button(param_name)) @@ -208,50 +212,56 @@ def __update_table(self, params, fc_parameters): column[6].grid(row=i, column=6, sticky="ew", padx=(0, 5)) # Add the "Add" button at the bottom of the table - add_button = ttk.Button(self.view_port, text=_("Add"), style='narrow.TButton', - command=lambda: self.__on_parameter_add(fc_parameters)) + add_button = ttk.Button( + self.view_port, text=_("Add"), style="narrow.TButton", command=lambda: self.__on_parameter_add(fc_parameters) + ) tooltip_msg = _("Add a parameter to the {self.current_file} file") show_tooltip(add_button, tooltip_msg.format(**locals())) - add_button.grid(row=len(params)+2, column=0, sticky="w", padx=0) - + add_button.grid(row=len(params) + 2, column=0, sticky="w", padx=0) except KeyError as e: logging_critical(_("Parameter %s not found in the %s file: %s"), param_name, self.current_file, e, exc_info=True) sys_exit(1) # Configure the table_frame to stretch columns - self.view_port.columnconfigure(0, weight=0) # Delete and Add buttons - self.view_port.columnconfigure(1, weight=0, minsize=120) # Parameter name - self.view_port.columnconfigure(2, weight=0) # Current Value - self.view_port.columnconfigure(3, weight=0) # New Value - self.view_port.columnconfigure(4, weight=0) # Units - self.view_port.columnconfigure(5, weight=0) # Upload to FC - self.view_port.columnconfigure(6, weight=1) # Change Reason + self.view_port.columnconfigure(0, weight=0) # Delete and Add buttons + self.view_port.columnconfigure(1, weight=0, minsize=120) # Parameter name + self.view_port.columnconfigure(2, weight=0) # Current Value + self.view_port.columnconfigure(3, weight=0) # New Value + self.view_port.columnconfigure(4, weight=0) # Units + self.view_port.columnconfigure(5, weight=0) # Upload to FC + self.view_port.columnconfigure(6, weight=1) # Change Reason def __create_delete_button(self, param_name): - delete_button = ttk.Button(self.view_port, text=_("Del"), style='narrow.TButton', - command=lambda: self.__on_parameter_delete(param_name)) + delete_button = ttk.Button( + self.view_port, text=_("Del"), style="narrow.TButton", command=lambda: self.__on_parameter_delete(param_name) + ) tooltip_msg = _("Delete {param_name} from the {self.current_file} file") show_tooltip(delete_button, tooltip_msg.format(**locals())) return delete_button def __create_parameter_name(self, param_name, param_metadata, doc_tooltip): - is_calibration = param_metadata.get('Calibration', False) if param_metadata else False - is_readonly = param_metadata.get('ReadOnly', False) if param_metadata else False - parameter_label = ttk.Label(self.view_port, text=param_name + (" " * (16 - len(param_name))), - background="red" if is_readonly else "yellow" if is_calibration else - ttk.Style(self.root).lookup('TFrame', 'background')) + is_calibration = param_metadata.get("Calibration", False) if param_metadata else False + is_readonly = param_metadata.get("ReadOnly", False) if param_metadata else False + parameter_label = ttk.Label( + self.view_port, + text=param_name + (" " * (16 - len(param_name))), + background="red" + if is_readonly + else "yellow" + if is_calibration + else ttk.Style(self.root).lookup("TFrame", "background"), + ) if doc_tooltip: show_tooltip(parameter_label, doc_tooltip) return parameter_label def __create_flightcontroller_value(self, fc_parameters, param_name, param_default, doc_tooltip): if param_name in fc_parameters: - value_str = format(fc_parameters[param_name], '.6f').rstrip('0').rstrip('.') + value_str = format(fc_parameters[param_name], ".6f").rstrip("0").rstrip(".") if param_default is not None and is_within_tolerance(fc_parameters[param_name], param_default.value): # If it matches, set the background color to light blue - flightcontroller_value = ttk.Label(self.view_port, text=value_str, - background="light blue") + flightcontroller_value = ttk.Label(self.view_port, text=value_str, background="light blue") else: # Otherwise, set the background color to the default color flightcontroller_value = ttk.Label(self.view_port, text=value_str) @@ -265,11 +275,11 @@ def __update_combobox_style_on_selection(self, combobox_widget, param_default, e try: current_value = float(combobox_widget.get_selected_key()) has_default_value = param_default is not None and is_within_tolerance(current_value, param_default.value) - combobox_widget.configure(style='default_v.TCombobox' if has_default_value else 'readonly.TCombobox') + combobox_widget.configure(style="default_v.TCombobox" if has_default_value else "readonly.TCombobox") event.width = NEW_VALUE_WIDGET_WIDTH combobox_widget.on_combo_configure(event) except ValueError: - msg = _('Could not solve the selected {combobox_widget} key to a float value.') + msg = _("Could not solve the selected {combobox_widget} key to a float value.") logging_info(msg.format(**locals())) @staticmethod @@ -277,67 +287,95 @@ def __update_new_value_entry_text(new_value_entry: ttk.Entry, value: float, para if isinstance(new_value_entry, PairTupleCombobox): return new_value_entry.delete(0, tk.END) - value_str = format(value, '.6f').rstrip('0').rstrip('.') + value_str = format(value, ".6f").rstrip("0").rstrip(".") new_value_entry.insert(0, value_str) if param_default is not None and is_within_tolerance(value, param_default.value): - new_value_entry.configure(style='default_v.TEntry') + new_value_entry.configure(style="default_v.TEntry") else: - new_value_entry.configure(style='TEntry') - - def __create_new_value_entry(self, param_name, param, # pylint: disable=too-many-arguments - param_metadata, param_default, doc_tooltip): - + new_value_entry.configure(style="TEntry") + + def __create_new_value_entry( # pylint: disable=too-many-arguments + self, + param_name, + param, + param_metadata, + param_default, + doc_tooltip, + ): present_as_forced = False - if self.current_file in self.local_filesystem.forced_parameters and \ - param_name in self.local_filesystem.forced_parameters[self.current_file]: + if ( + self.current_file in self.local_filesystem.forced_parameters + and param_name in self.local_filesystem.forced_parameters[self.current_file] + ): present_as_forced = True - if not is_within_tolerance(param.value, - self.local_filesystem.forced_parameters[self.current_file][param_name].value): + if not is_within_tolerance( + param.value, self.local_filesystem.forced_parameters[self.current_file][param_name].value + ): param.value = self.local_filesystem.forced_parameters[self.current_file][param_name].value self.at_least_one_param_edited = True - if self.current_file in self.local_filesystem.derived_parameters and \ - param_name in self.local_filesystem.derived_parameters[self.current_file]: + if ( + self.current_file in self.local_filesystem.derived_parameters + and param_name in self.local_filesystem.derived_parameters[self.current_file] + ): present_as_forced = True - if not is_within_tolerance(param.value, - self.local_filesystem.derived_parameters[self.current_file][param_name].value): + if not is_within_tolerance( + param.value, self.local_filesystem.derived_parameters[self.current_file][param_name].value + ): param.value = self.local_filesystem.derived_parameters[self.current_file][param_name].value self.at_least_one_param_edited = True bitmask_dict = None - value_str = format(param.value, '.6f').rstrip('0').rstrip('.') - if param_metadata and 'values' in param_metadata and param_metadata['values'] and \ - value_str in param_metadata['values']: - selected_value = param_metadata['values'].get(value_str, None) + value_str = format(param.value, ".6f").rstrip("0").rstrip(".") + if ( + param_metadata + and "values" in param_metadata + and param_metadata["values"] + and value_str in param_metadata["values"] + ): + selected_value = param_metadata["values"].get(value_str, None) has_default_value = param_default is not None and is_within_tolerance(param.value, param_default.value) - new_value_entry = PairTupleCombobox(self.view_port, param_metadata['values'], - value_str, param_name, - style='TCombobox' if present_as_forced else \ - 'default_v.TCombobox' if has_default_value else 'readonly.TCombobox') + new_value_entry = PairTupleCombobox( + self.view_port, + param_metadata["values"], + value_str, + param_name, + style="TCombobox" + if present_as_forced + else "default_v.TCombobox" + if has_default_value + else "readonly.TCombobox", + ) new_value_entry.set(selected_value) font = get_widget_font(new_value_entry) - font['size'] -= 2 if platform_system() == 'Windows' else 1 - new_value_entry.config(state='readonly', width=NEW_VALUE_WIDGET_WIDTH, font=(font['family'], font['size'])) - new_value_entry.bind("<>", - lambda event: self.__update_combobox_style_on_selection(new_value_entry, param_default, - event), '+') + font["size"] -= 2 if platform_system() == "Windows" else 1 + new_value_entry.config(state="readonly", width=NEW_VALUE_WIDGET_WIDTH, font=(font["family"], font["size"])) + new_value_entry.bind( + "<>", + lambda event: self.__update_combobox_style_on_selection(new_value_entry, param_default, event), + "+", + ) else: - new_value_entry = ttk.Entry(self.view_port, width=NEW_VALUE_WIDGET_WIDTH+1, justify=tk.RIGHT) + new_value_entry = ttk.Entry(self.view_port, width=NEW_VALUE_WIDGET_WIDTH + 1, justify=tk.RIGHT) ParameterEditorTable.__update_new_value_entry_text(new_value_entry, param.value, param_default) - bitmask_dict = param_metadata.get('Bitmask', None) if param_metadata else None + bitmask_dict = param_metadata.get("Bitmask", None) if param_metadata else None try: old_value = self.local_filesystem.file_parameters[self.current_file][param_name].value except KeyError as e: logging_critical(_("Parameter %s not found in the %s file: %s"), param_name, self.current_file, e, exc_info=True) sys_exit(1) if present_as_forced: - new_value_entry.config(state='disabled', background='light grey') + new_value_entry.config(state="disabled", background="light grey") + elif bitmask_dict: + new_value_entry.bind( + "", lambda event: self.__open_bitmask_selection_window(event, param_name, bitmask_dict, old_value) + ) else: - if bitmask_dict: - new_value_entry.bind("", lambda event: - self.__open_bitmask_selection_window(event, param_name, bitmask_dict, old_value)) - else: - new_value_entry.bind("", lambda event, current_file=self.current_file, param_name=param_name: - self.__on_parameter_value_change(event, current_file, param_name)) + new_value_entry.bind( + "", + lambda event, current_file=self.current_file, param_name=param_name: self.__on_parameter_value_change( + event, current_file, param_name + ), + ) if doc_tooltip: show_tooltip(new_value_entry, doc_tooltip) return new_value_entry @@ -348,9 +386,9 @@ def on_close(): # Convert checked keys back to a decimal value new_decimal_value = sum(1 << key for key in checked_keys) # Update new_value_entry with the new decimal value - ParameterEditorTable.__update_new_value_entry_text(event.widget, - new_decimal_value, - self.local_filesystem.param_default_dict.get(param_name, None)) + ParameterEditorTable.__update_new_value_entry_text( + event.widget, new_decimal_value, self.local_filesystem.param_default_dict.get(param_name, None) + ) self.at_least_one_param_edited = (old_value != new_decimal_value) or self.at_least_one_param_edited self.local_filesystem.file_parameters[self.current_file][param_name].value = new_decimal_value # Destroy the window @@ -360,8 +398,9 @@ def on_close(): # Run the Tk event loop once to process the event self.root.update_idletasks() # Re-bind the FocusIn event to new_value_entry - event.widget.bind("", lambda event: - self.__open_bitmask_selection_window(event, param_name, bitmask_dict, old_value)) + event.widget.bind( + "", lambda event: self.__open_bitmask_selection_window(event, param_name, bitmask_dict, old_value) + ) def get_param_value_msg(_param_name, checked_keys) -> str: _new_decimal_value = sum(1 << key for key in checked_keys) @@ -404,12 +443,15 @@ def update_label(): self.root.update_idletasks() window.grab_set() - window.wait_window() # Wait for the window to be closed + window.wait_window() # Wait for the window to be closed def __create_unit_label(self, param_metadata): - unit_label = ttk.Label(self.view_port, text=param_metadata.get('unit') if param_metadata else "") - unit_tooltip = param_metadata.get('unit_tooltip') if param_metadata else \ - _("No documentation available in apm.pdef.xml for this parameter") + unit_label = ttk.Label(self.view_port, text=param_metadata.get("unit") if param_metadata else "") + unit_tooltip = ( + param_metadata.get("unit_tooltip") + if param_metadata + else _("No documentation available in apm.pdef.xml for this parameter") + ) if unit_tooltip: show_tooltip(unit_label, unit_tooltip) return unit_label @@ -417,22 +459,25 @@ def __create_unit_label(self, param_metadata): def __create_upload_checkbutton(self, param_name, fc_connected): self.upload_checkbutton_var[param_name] = tk.BooleanVar(value=fc_connected) upload_checkbutton = ttk.Checkbutton(self.view_port, variable=self.upload_checkbutton_var[param_name]) - upload_checkbutton.configure(state='normal' if fc_connected else 'disabled') - msg = _('When selected upload {param_name} new value to the flight controller') + upload_checkbutton.configure(state="normal" if fc_connected else "disabled") + msg = _("When selected upload {param_name} new value to the flight controller") show_tooltip(upload_checkbutton, msg.format(**locals())) return upload_checkbutton def __create_change_reason_entry(self, param_name, param, new_value_entry): - present_as_forced = False - if self.current_file in self.local_filesystem.forced_parameters and \ - param_name in self.local_filesystem.forced_parameters[self.current_file]: + if ( + self.current_file in self.local_filesystem.forced_parameters + and param_name in self.local_filesystem.forced_parameters[self.current_file] + ): present_as_forced = True if param.comment != self.local_filesystem.forced_parameters[self.current_file][param_name].comment: param.comment = self.local_filesystem.forced_parameters[self.current_file][param_name].comment self.at_least_one_param_edited = True - if self.current_file in self.local_filesystem.derived_parameters and \ - param_name in self.local_filesystem.derived_parameters[self.current_file]: + if ( + self.current_file in self.local_filesystem.derived_parameters + and param_name in self.local_filesystem.derived_parameters[self.current_file] + ): present_as_forced = True if param.comment != self.local_filesystem.derived_parameters[self.current_file][param_name].comment: param.comment = self.local_filesystem.derived_parameters[self.current_file][param_name].comment @@ -441,12 +486,16 @@ def __create_change_reason_entry(self, param_name, param, new_value_entry): change_reason_entry = ttk.Entry(self.view_port, background="white") change_reason_entry.insert(0, "" if param.comment is None else param.comment) if present_as_forced: - change_reason_entry.config(state='disabled', background='light grey') + change_reason_entry.config(state="disabled", background="light grey") else: - change_reason_entry.bind("", lambda event, current_file=self.current_file, param_name=param_name: - self.__on_parameter_change_reason_change(event, current_file, param_name)) + change_reason_entry.bind( + "", + lambda event, current_file=self.current_file, param_name=param_name: self.__on_parameter_change_reason_change( + event, current_file, param_name + ), + ) _value = new_value_entry.get() - msg = _('Reason why {param_name} should change to {_value}') + msg = _("Reason why {param_name} should change to {_value}") show_tooltip(change_reason_entry, msg.format(**locals())) return change_reason_entry @@ -479,21 +528,30 @@ def __on_parameter_add(self, fc_parameters): param_dict = fc_parameters if not param_dict: - messagebox.showerror(_("Operation not possible"), - _("No apm.pdef.xml file and no FC connected. Not possible autocomplete parameter names.")) + messagebox.showerror( + _("Operation not possible"), + _("No apm.pdef.xml file and no FC connected. Not possible autocomplete parameter names."), + ) return # Remove the parameters that are already displayed in this configuration step - possible_add_param_names = [param_name for param_name in param_dict \ - if param_name not in self.local_filesystem.file_parameters[self.current_file]] + possible_add_param_names = [ + param_name + for param_name in param_dict + if param_name not in self.local_filesystem.file_parameters[self.current_file] + ] possible_add_param_names.sort() # Prompt the user for a parameter name - parameter_name_combobox = EntryWithDynamicalyFilteredListbox(add_parameter_window.main_frame, - possible_add_param_names, - startswith_match=False, ignorecase_match=True, - listbox_height=12, width=28) + parameter_name_combobox = EntryWithDynamicalyFilteredListbox( + add_parameter_window.main_frame, + possible_add_param_names, + startswith_match=False, + ignorecase_match=True, + listbox_height=12, + width=28, + ) parameter_name_combobox.pack(padx=5, pady=5) BaseWindow.center_window(add_parameter_window.root, self.root) parameter_name_combobox.focus() @@ -525,16 +583,19 @@ def __confirm_parameter_addition(self, param_name: str, fc_parameters: dict) -> messagebox.showerror(_("Invalid parameter name."), _("Parameter name not found in the flight controller.")) elif self.local_filesystem.doc_dict: if param_name in self.local_filesystem.doc_dict: - self.local_filesystem.file_parameters[self.current_file][param_name] = Par( \ - self.local_filesystem.param_default_dict.get(param_name, Par(0, "")).value, "") + self.local_filesystem.file_parameters[self.current_file][param_name] = Par( + self.local_filesystem.param_default_dict.get(param_name, Par(0, "")).value, "" + ) self.at_least_one_param_edited = True self.parameter_editor.repopulate_parameter_table(self.current_file) return True error_msg = _("'{param_name}' not found in the apm.pdef.xml file.") messagebox.showerror(_("Invalid parameter name."), error_msg.format(**locals())) else: - messagebox.showerror(_("Operation not possible"), - _("Can not add parameter when no FC is connected and no apm.pdef.xml file exists.")) + messagebox.showerror( + _("Operation not possible"), + _("Can not add parameter when no FC is connected and no apm.pdef.xml file exists."), + ) return False def __on_parameter_value_change(self, event, current_file, param_name): @@ -554,18 +615,20 @@ def __on_parameter_value_change(self, event, current_file, param_name): p = float(new_value) changed = not is_within_tolerance(old_value, p) param_metadata = self.local_filesystem.doc_dict.get(param_name, None) - p_min = param_metadata.get('min', None) if param_metadata else None - p_max = param_metadata.get('max', None) if param_metadata else None + p_min = param_metadata.get("min", None) if param_metadata else None + p_max = param_metadata.get("max", None) if param_metadata else None if changed: if p_min and p < p_min: msg = _("The value for {param_name} {p} should be greater than {p_min}\n") - if not messagebox.askyesno(_("Out-of-bounds Value"), - msg.format(**locals()) + _("Use out-of-bounds value?"), icon='warning'): + if not messagebox.askyesno( + _("Out-of-bounds Value"), msg.format(**locals()) + _("Use out-of-bounds value?"), icon="warning" + ): valid = False if p_max and p > p_max: msg = _("The value for {param_name} {p} should be smaller than {p_max}\n") - if not messagebox.askyesno(_("Out-of-bounds Value"), - msg.format(**locals()) + _("Use out-of-bounds value?"), icon='warning'): + if not messagebox.askyesno( + _("Out-of-bounds Value"), msg.format(**locals()) + _("Use out-of-bounds value?"), icon="warning" + ): valid = False except ValueError: # Optionally, you can handle the invalid value here, for example, by showing an error message @@ -587,16 +650,21 @@ def __on_parameter_change_reason_change(self, event, current_file, param_name): # Get the new value from the Entry widget new_value = event.widget.get() try: - changed = new_value != self.local_filesystem.file_parameters[current_file][param_name].comment and \ - not (new_value == "" and self.local_filesystem.file_parameters[current_file][param_name].comment is None) + changed = new_value != self.local_filesystem.file_parameters[current_file][param_name].comment and not ( + new_value == "" and self.local_filesystem.file_parameters[current_file][param_name].comment is None + ) except KeyError as e: - logging_critical(_("Parameter %s not found in the %s file %s: %s"), param_name, current_file, - new_value, e, exc_info=True) + logging_critical( + _("Parameter %s not found in the %s file %s: %s"), param_name, current_file, new_value, e, exc_info=True + ) sys_exit(1) if changed and not self.at_least_one_param_edited: - logging_debug(_("Parameter %s change reason changed from %s to %s, will later ask if change(s) should be saved to " - "file."), - param_name, self.local_filesystem.file_parameters[current_file][param_name].comment, new_value) + logging_debug( + _("Parameter %s change reason changed from %s to %s, will later ask if change(s) should be saved to file."), + param_name, + self.local_filesystem.file_parameters[current_file][param_name].comment, + new_value, + ) self.at_least_one_param_edited = changed or self.at_least_one_param_edited # Update the params dictionary with the new value self.local_filesystem.file_parameters[current_file][param_name].comment = new_value diff --git a/MethodicConfigurator/frontend_tkinter_template_overview.py b/MethodicConfigurator/frontend_tkinter_template_overview.py index cf09151..cd21215 100644 --- a/MethodicConfigurator/frontend_tkinter_template_overview.py +++ b/MethodicConfigurator/frontend_tkinter_template_overview.py @@ -1,33 +1,28 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" import argparse +import tkinter as tk from logging import basicConfig as logging_basicConfig from logging import getLevelName as logging_getLevelName - -import tkinter as tk from tkinter import ttk -from MethodicConfigurator.middleware_template_overview import TemplateOverview - from MethodicConfigurator.backend_filesystem_program_settings import ProgramSettings from MethodicConfigurator.backend_filesystem_vehicle_components import VehicleComponents - from MethodicConfigurator.common_arguments import add_common_arguments_and_parse - from MethodicConfigurator.frontend_tkinter_base import BaseWindow - -from MethodicConfigurator.internationalization import _ - +from MethodicConfigurator import _ +from MethodicConfigurator.middleware_template_overview import TemplateOverview from MethodicConfigurator.version import VERSION + class TemplateOverviewWindow(BaseWindow): """ Represents the window for viewing and managing ArduPilot vehicle templates. @@ -44,6 +39,7 @@ class TemplateOverviewWindow(BaseWindow): on_row_double_click(event): Handles the event triggered when a row in the Treeview is double-clicked, allowing the user to store the corresponding template directory. """ + def __init__(self, parent: tk.Tk): super().__init__(parent) title = _("Amilcar Lucas's - ArduPilot methodic configurator {} - Template Overview and selection") @@ -51,39 +47,54 @@ def __init__(self, parent: tk.Tk): self.root.geometry("1200x300") instruction_text = _("Please double-click the template below that most resembles your own vehicle components") - instruction_label = ttk.Label(self.main_frame, text=instruction_text, font=('Arial', 12)) + instruction_label = ttk.Label(self.main_frame, text=instruction_text, font=("Arial", 12)) instruction_label.pack(pady=(10, 20)) self.sort_column = None style = ttk.Style(self.root) # Add padding to Treeview heading style - style.layout("Treeview.Heading", [ - ("Treeview.Heading.cell", {'sticky': 'nswe'}), - ("Treeview.Heading.border", {'sticky':'nswe', 'children': [ - ("Treeview.Heading.padding", {'sticky':'nswe', 'children': [ - ("Treeview.Heading.image", {'side':'right', 'sticky':''}), - ("Treeview.Heading.text", {'sticky':'we'}) - ]}) - ]}), - ]) - style.configure("Treeview.Heading", padding=[2, 2, 2, 18], justify='center') + style.layout( + "Treeview.Heading", + [ + ("Treeview.Heading.cell", {"sticky": "nswe"}), + ( + "Treeview.Heading.border", + { + "sticky": "nswe", + "children": [ + ( + "Treeview.Heading.padding", + { + "sticky": "nswe", + "children": [ + ("Treeview.Heading.image", {"side": "right", "sticky": ""}), + ("Treeview.Heading.text", {"sticky": "we"}), + ], + }, + ) + ], + }, + ), + ], + ) + style.configure("Treeview.Heading", padding=[2, 2, 2, 18], justify="center") # Define the columns for the Treeview columns = TemplateOverview.columns() - self.tree = ttk.Treeview(self.main_frame, columns=columns, show='headings') + self.tree = ttk.Treeview(self.main_frame, columns=columns, show="headings") for col in columns: self.tree.heading(col, text=col) # Populate the Treeview with data from the template overview for key, template_overview in VehicleComponents.get_vehicle_components_overviews().items(): attribute_names = template_overview.attributes() - values = (key,) + tuple(getattr(template_overview, attr, '') for attr in attribute_names) - self.tree.insert('', 'end', text=key, values=values) + values = (key,) + tuple(getattr(template_overview, attr, "") for attr in attribute_names) + self.tree.insert("", "end", text=key, values=values) self.__adjust_treeview_column_widths() - self.tree.bind('', self.__on_row_double_click) + self.tree.bind("", self.__on_row_double_click) self.tree.pack(fill=tk.BOTH, expand=True) for col in self.tree["columns"]: @@ -105,41 +116,41 @@ def __adjust_treeview_column_widths(self): """ for col in self.tree["columns"]: max_width = 0 - for subtitle in col.title().split('\n'): + for subtitle in col.title().split("\n"): max_width = max(max_width, tk.font.Font().measure(subtitle)) # Iterate over all rows and update the max_width if a wider entry is found for item in self.tree.get_children(): - item_text = self.tree.item(item, 'values')[self.tree["columns"].index(col)] + item_text = self.tree.item(item, "values")[self.tree["columns"].index(col)] text_width = tk.font.Font().measure(item_text) max_width = max(max_width, text_width) # Update the column's width property to accommodate the largest text width - self.tree.column(col, width=int(max_width*0.6 + 10)) + self.tree.column(col, width=int(max_width * 0.6 + 10)) def __on_row_double_click(self, event): """Handle row double-click event.""" item_id = self.tree.identify_row(event.y) if item_id: - selected_template_relative_path = self.tree.item(item_id)['text'] + selected_template_relative_path = self.tree.item(item_id)["text"] ProgramSettings.store_template_dir(selected_template_relative_path) self.root.destroy() def __sort_by_column(self, col, reverse: bool): - if self.sort_column and self.sort_column != col: + if self.sort_column and self.sort_column != col: self.tree.heading(self.sort_column, text=self.sort_column) - self.tree.heading(col, text=col + (' ▼' if reverse else ' ▲')) + self.tree.heading(col, text=col + (" ▼" if reverse else " ▲")) self.sort_column = col try: - col_data = [(float(self.tree.set(k, col)), k) for k in self.tree.get_children('')] + col_data = [(float(self.tree.set(k, col)), k) for k in self.tree.get_children("")] except ValueError: - col_data = [(self.tree.set(k, col), k) for k in self.tree.get_children('')] + col_data = [(self.tree.set(k, col), k) for k in self.tree.get_children("")] col_data.sort(reverse=reverse) # rearrange items in sorted positions for index, (_val, k) in enumerate(col_data): - self.tree.move(k, '', index) + self.tree.move(k, "", index) # reverse sort next time self.tree.heading(col, command=lambda: self.__sort_by_column(col, not reverse)) @@ -154,19 +165,23 @@ def argument_parser(): Returns: argparse.Namespace: An object containing the parsed arguments. """ - parser = argparse.ArgumentParser(description=_('ArduPilot methodic configurator is a GUI-based tool designed to simplify ' - 'the management and visualization of ArduPilot parameters. It enables users ' - 'to browse through various vehicle templates, edit parameter files, and ' - 'apply changes directly to the flight controller. The tool is built to ' - 'semi-automate the configuration process of ArduPilot for drones by ' - 'providing a clear and intuitive interface for parameter management.')) + parser = argparse.ArgumentParser( + description=_( + "ArduPilot methodic configurator is a GUI-based tool designed to simplify " + "the management and visualization of ArduPilot parameters. It enables users " + "to browse through various vehicle templates, edit parameter files, and " + "apply changes directly to the flight controller. The tool is built to " + "semi-automate the configuration process of ArduPilot for drones by " + "providing a clear and intuitive interface for parameter management." + ) + ) return add_common_arguments_and_parse(parser) def main(): args = argument_parser() - logging_basicConfig(level=logging_getLevelName(args.loglevel), format='%(asctime)s - %(levelname)s - %(message)s') + logging_basicConfig(level=logging_getLevelName(args.loglevel), format="%(asctime)s - %(levelname)s - %(message)s") TemplateOverviewWindow(None) diff --git a/MethodicConfigurator/get_release_stats.py b/MethodicConfigurator/get_release_stats.py index 8251345..fe214d2 100755 --- a/MethodicConfigurator/get_release_stats.py +++ b/MethodicConfigurator/get_release_stats.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 -''' +""" Based on https://pagure.io/github-release-stats/blob/master/f/get_release_stats.py by Clement Verna This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator @@ -8,11 +8,10 @@ SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" import itertools import re - from operator import itemgetter from github import Github diff --git a/MethodicConfigurator/internationalization.py b/MethodicConfigurator/internationalization.py index 317e940..2cda2df 100644 --- a/MethodicConfigurator/internationalization.py +++ b/MethodicConfigurator/internationalization.py @@ -1,22 +1,21 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" import argparse import gettext from os import path as os_path -import builtins # Do not import nor use logging functions in this file. # Logging is not yet configured when these functions are called -LANGUAGE_CHOICES = ['en', 'zh_CN', 'pt'] +LANGUAGE_CHOICES = ["en", "zh_CN", "pt"] def identity_function(s): @@ -24,11 +23,11 @@ def identity_function(s): def load_translation() -> callable: - default_language = 'en' + default_language = LANGUAGE_CHOICES[0] # First, pre-parse to find the --language argument pre_parser = argparse.ArgumentParser(add_help=False) - pre_parser.add_argument('--language', type=str, default=default_language, choices=LANGUAGE_CHOICES) + pre_parser.add_argument("--language", type=str, default=default_language, choices=LANGUAGE_CHOICES) pre_args, _list_str = pre_parser.parse_known_args() if pre_args.language == default_language: @@ -37,21 +36,17 @@ def load_translation() -> callable: # Load the correct language ASAP based on the command line argument try: script_dir = os_path.dirname(os_path.abspath(__file__)) - locale_dir = os_path.join(script_dir, 'locale') - translation = gettext.translation('MethodicConfigurator', localedir=locale_dir, - languages=[pre_args.language], fallback=False) + locale_dir = os_path.join(script_dir, "locale") + translation = gettext.translation( + "MethodicConfigurator", localedir=locale_dir, languages=[pre_args.language], fallback=False + ) translation.install() # Do not use logging functions here the logging system has not been configured yet # Do not translate this message, the translation will not work here anyways - print("Loaded %s translation.", pre_args.language) + print(f"Loaded {pre_args.language} translation files.") return translation.gettext except FileNotFoundError: # Do not use logging functions here the logging system has not been configured yet # Do not translate this message, the translation will not work here anyways - print("Translation files not found for the selected language. Falling back to default.") + print(f"{pre_args.language} translation files not found. Using default {default_language} language.") return identity_function # Return identity function on error - - -# Default to identity function if _ is not already defined -if '_' not in globals() and '_' not in locals() and '_' not in builtins.__dict__: - _ = load_translation() diff --git a/MethodicConfigurator/locale/pt/LC_MESSAGES/MethodicConfigurator.po b/MethodicConfigurator/locale/pt/LC_MESSAGES/MethodicConfigurator.po index 2f2f94a..0c89855 100644 --- a/MethodicConfigurator/locale/pt/LC_MESSAGES/MethodicConfigurator.po +++ b/MethodicConfigurator/locale/pt/LC_MESSAGES/MethodicConfigurator.po @@ -792,8 +792,8 @@ msgid "" "No parameter values will be fetched from the FC, default parameter values from disk will be used\n" "instead (if '00_default.param' file is present) and just edit the intermediate '.param' files on disk" msgstr "" -"Não serão buscados valores de parâmetros do FC, serão utilizados os valores padrão dos parâmetros em disco\n" -"em vez disso (se o arquivo '00_default.param' estiver presente) e você pode apenas editar os arquivos intermediários '.param' no disco." +"Não serão buscados valores de parâmetros do FC, em vez disso serão utilizados os valores padrão dos parâmetros em disco\n" +"(se o arquivo '00_default.param' estiver presente) e você pode apenas editar os arquivos intermediários '.param' no disco." #: MethodicConfigurator/frontend_tkinter_connection_selection.py:263 msgid "Will proceed without FC connection. FC parameters will not be downloaded nor uploaded" diff --git a/MethodicConfigurator/locale/pt/LC_MESSAGES/extract_missing_translations.py b/MethodicConfigurator/locale/pt/LC_MESSAGES/extract_missing_translations.py index 04da9f9..64c9fa8 100644 --- a/MethodicConfigurator/locale/pt/LC_MESSAGES/extract_missing_translations.py +++ b/MethodicConfigurator/locale/pt/LC_MESSAGES/extract_missing_translations.py @@ -1,31 +1,32 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" -import os import gettext +import os + def extract_missing_translations(po_file, output_file): # Set up the translation catalog - language = gettext.translation('messages', localedir=os.path.dirname(po_file), languages=['zh_CN'], fallback=True) + language = gettext.translation("messages", localedir=os.path.dirname(po_file), languages=["zh_CN"], fallback=True) # Read the .po file entries - with open(po_file, 'r', encoding='utf-8') as f: + with open(po_file, "r", encoding="utf-8") as f: lines = f.readlines() missing_translations = [] # Iterate through lines to find untranslated msgid - for i, line in enumerate(lines): - line = line.strip() + for i, f_line in enumerate(lines): + line = f_line.strip() - if line.startswith('msgid'): + if line.startswith("msgid"): msgid = line.split('"')[1] # Get the msgid string # Check if the translation exists @@ -33,9 +34,10 @@ def extract_missing_translations(po_file, output_file): missing_translations.append((i, msgid)) # Write untranslated msgids along with their indices to the output file - with open(output_file, 'w', encoding='utf-8') as f: + with open(output_file, "w", encoding="utf-8") as f: for index, item in missing_translations: - f.write(f'{index}:{item}\n') + f.write(f"{index}:{item}\n") + if __name__ == "__main__": - extract_missing_translations('MethodicConfigurator.po', 'missing_translations.txt') + extract_missing_translations("MethodicConfigurator.po", "missing_translations.txt") diff --git a/MethodicConfigurator/locale/pt/LC_MESSAGES/insert_translations.py b/MethodicConfigurator/locale/pt/LC_MESSAGES/insert_translations.py index e79dd76..33bc495 100644 --- a/MethodicConfigurator/locale/pt/LC_MESSAGES/insert_translations.py +++ b/MethodicConfigurator/locale/pt/LC_MESSAGES/insert_translations.py @@ -1,24 +1,25 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" + def insert_translations(po_file, translations_file, output_file): - with open(po_file, 'r', encoding='utf-8') as f: + with open(po_file, "r", encoding="utf-8") as f: lines = f.readlines() - with open(translations_file, 'r', encoding='utf-8') as f: - translations_data = f.read().strip().split('\n') + with open(translations_file, "r", encoding="utf-8") as f: + translations_data = f.read().strip().split("\n") # Prepare to insert translations translations = [] for data in translations_data: - index, translation = data.split(':', 1) # Split the index and the translation + index, translation = data.split(":", 1) # Split the index and the translation translations.append((int(index), translation.strip())) # Store index and translation as tuple insertion_offset = 0 # To track how many lines we've inserted @@ -28,8 +29,7 @@ def insert_translations(po_file, translations_file, output_file): adjusted_index = index + insertion_offset # Check if the next line is an empty msgstr - if (adjusted_index + 1 < len(lines) and - lines[adjusted_index + 1].strip() == 'msgstr ""'): + if adjusted_index + 1 < len(lines) and lines[adjusted_index + 1].strip() == 'msgstr ""': # Overwrite the empty msgstr line lines[adjusted_index + 1] = f'msgstr "{translation}"\n' else: @@ -38,8 +38,9 @@ def insert_translations(po_file, translations_file, output_file): insertion_offset += 1 # Increment the offset for each insertion # Writing back to a new output file - with open(output_file, 'w', encoding='utf-8') as f: + with open(output_file, "w", encoding="utf-8") as f: f.writelines(lines) + if __name__ == "__main__": - insert_translations('MethodicConfigurator.po', 'translations.txt', 'updated_MethodicConfigurator.po') + insert_translations("MethodicConfigurator.po", "translations.txt", "updated_MethodicConfigurator.po") diff --git a/MethodicConfigurator/mavftp_example.py b/MethodicConfigurator/mavftp_example.py index db807bc..46dedc6 100755 --- a/MethodicConfigurator/mavftp_example.py +++ b/MethodicConfigurator/mavftp_example.py @@ -1,31 +1,27 @@ #!/usr/bin/env python3 -''' +""" MAVLink File Transfer Protocol support example SPDX-FileCopyrightText: 2024 Amilcar Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" +import os +import sys from argparse import ArgumentParser - from logging import basicConfig as logging_basicConfig -from logging import getLevelName as logging_getLevelName - from logging import debug as logging_debug -from logging import info as logging_info from logging import error as logging_error +from logging import getLevelName as logging_getLevelName +from logging import info as logging_info -import os -import sys -#import time +import backend_mavftp as mavftp +# import time import requests - - from pymavlink import mavutil -import backend_mavftp as mavftp old_mavftp_member_variable_values = {} @@ -35,38 +31,47 @@ def argument_parser(): """ Parses command-line arguments for the script. """ - parser = ArgumentParser(description='This main is just an example, adapt it to your needs') - parser.add_argument("--baudrate", type=int, default=115200, - help="master port baud rate. Defaults to %(default)s") - parser.add_argument("--device", type=str, default='', - help="serial device. For windows use COMx where x is the port number. " - "For Unix use /dev/ttyUSBx where x is the port number. Defaults to autodetection") - parser.add_argument("--source-system", type=int, default=250, - help='MAVLink source system for this GCS. Defaults to %(default)s') - parser.add_argument("--loglevel", default="INFO", - help="log level. Defaults to %(default)s") + parser = ArgumentParser(description="This main is just an example, adapt it to your needs") + parser.add_argument("--baudrate", type=int, default=115200, help="master port baud rate. Defaults to %(default)s") + parser.add_argument( + "--device", + type=str, + default="", + help="serial device. For windows use COMx where x is the port number. " + "For Unix use /dev/ttyUSBx where x is the port number. Defaults to autodetection", + ) + parser.add_argument( + "--source-system", type=int, default=250, help="MAVLink source system for this GCS. Defaults to %(default)s" + ) + parser.add_argument("--loglevel", default="INFO", help="log level. Defaults to %(default)s") # MAVFTP settings - parser.add_argument("--debug", type=int, default=0, choices=[0, 1, 2], - help="Debug level 0 for none, 2 for max verbosity. Defaults to %(default)s") + parser.add_argument( + "--debug", + type=int, + default=0, + choices=[0, 1, 2], + help="Debug level 0 for none, 2 for max verbosity. Defaults to %(default)s", + ) return parser.parse_args() + def auto_detect_serial(): preferred_ports = [ - '*FTDI*', + "*FTDI*", "*3D*", "*USB_to_UART*", - '*Ardu*', - '*PX4*', - '*Hex_*', - '*Holybro_*', - '*mRo*', - '*FMU*', - '*Swift-Flyer*', - '*Serial*', - '*CubePilot*', - '*Qiotek*', + "*Ardu*", + "*PX4*", + "*Hex_*", + "*Holybro_*", + "*mRo*", + "*FMU*", + "*Swift-Flyer*", + "*Serial*", + "*CubePilot*", + "*Qiotek*", ] serial_list = mavutil.auto_detect_serial(preferred_list=preferred_ports) serial_list.sort(key=lambda x: x.device) @@ -87,7 +92,7 @@ def auto_connect(device): autodetect_serial = auto_detect_serial() if autodetect_serial: # Resolve the soft link if it's a Linux system - if os.name == 'posix': + if os.name == "posix": try: dev = autodetect_serial[0].device logging_debug("Auto-detected device %s", dev) @@ -98,7 +103,7 @@ def auto_connect(device): autodetect_serial[0].device = resolved_path logging_debug("Resolved soft link %s to %s", dev, resolved_path) except OSError: - pass # Not a soft link, proceed with the original device path + pass # Not a soft link, proceed with the original device path comport = autodetect_serial[0] else: logging_error("No serial ports found. Please connect a flight controller and try again.") @@ -107,10 +112,12 @@ def auto_connect(device): def wait_heartbeat(m): - '''wait for a heartbeat so we know the target system IDs''' + """wait for a heartbeat so we know the target system IDs""" logging_info("Waiting for flight controller heartbeat") m.wait_heartbeat() logging_info("Got heartbeat from system %u, component %u", m.target_system, m.target_system) + + # pylint: enable=duplicate-code @@ -126,18 +133,18 @@ def get_list_dir(mav_ftp, directory): def get_file(mav_ftp, remote_filename, local_filename, timeout=5): - #session = mav_ftp.session # save the session to restore it after the file transfer + # session = mav_ftp.session # save the session to restore it after the file transfer mav_ftp.cmd_get([remote_filename, local_filename]) - ret = mav_ftp.process_ftp_reply('OpenFileRO', timeout=timeout) + ret = mav_ftp.process_ftp_reply("OpenFileRO", timeout=timeout) ret.display_message() - #mav_ftp.session = session # FIXME: this is a huge workaround hack # pylint: disable=fixme + # mav_ftp.session = session # FIXME: this is a huge workaround hack # pylint: disable=fixme debug_class_member_variable_changes(mav_ftp) - #time.sleep(0.2) + # time.sleep(0.2) def get_last_log(mav_ftp): try: - with open('LASTLOG.TXT', 'r', encoding='UTF-8') as file: + with open("LASTLOG.TXT", "r", encoding="UTF-8") as file: file_contents = file.readline() remote_filenumber = int(file_contents.strip()) except FileNotFoundError: @@ -146,9 +153,9 @@ def get_last_log(mav_ftp): except ValueError: logging_error("Could not extract last log file number from LASTLOG.TXT contants %s", file_contents) return - remote_filenumber = remote_filenumber - 1 # we do not want the very last log - remote_filename = f'/APM/LOGS/{remote_filenumber:08}.BIN' - get_file(mav_ftp, remote_filename, 'LASTLOG.BIN', 0) + remote_filenumber = remote_filenumber - 1 # we do not want the very last log + remote_filename = f"/APM/LOGS/{remote_filenumber:08}.BIN" + get_file(mav_ftp, remote_filename, "LASTLOG.BIN", 0) def download_script(url, local_filename): @@ -176,8 +183,8 @@ def remove_directory(mav_ftp, remote_directory): def upload_script(mav_ftp, remote_directory, local_filename, timeout): # Upload it from the PC to the flight controller - mav_ftp.cmd_put([local_filename, remote_directory + '/' + local_filename]) - ret = mav_ftp.process_ftp_reply('CreateFile', timeout=timeout) + mav_ftp.cmd_put([local_filename, remote_directory + "/" + local_filename]) + ret = mav_ftp.process_ftp_reply("CreateFile", timeout=timeout) ret.display_message() debug_class_member_variable_changes(mav_ftp) @@ -203,11 +210,12 @@ def debug_class_member_variable_changes(instance): logging_info(f"CHANGED {key}: {old_mavftp_member_variable_values[key]} -> {value}") old_mavftp_member_variable_values = new_mavftp_member_variable_values.copy() + def main(): - '''for testing/example purposes only''' + """for testing/example purposes only""" args = argument_parser() - logging_basicConfig(level=logging_getLevelName(args.loglevel), format='%(levelname)s - %(message)s') + logging_basicConfig(level=logging_getLevelName(args.loglevel), format="%(levelname)s - %(message)s") # create a mavlink serial instance comport = auto_connect(args.device) @@ -216,35 +224,33 @@ def main(): # wait for the heartbeat msg to find the system ID wait_heartbeat(master) - mav_ftp = mavftp.MAVFTP(master, - target_system=master.target_system, - target_component=master.target_component) + mav_ftp = mavftp.MAVFTP(master, target_system=master.target_system, target_component=master.target_component) mav_ftp.ftp_settings.debug = args.debug - if args.loglevel == 'DEBUG': + if args.loglevel == "DEBUG": mav_ftp.ftp_settings.debug = 2 debug_class_member_variable_changes(mav_ftp) - get_list_dir(mav_ftp, '/APM/LOGS') + get_list_dir(mav_ftp, "/APM/LOGS") delete_local_file_if_exists("params.param") delete_local_file_if_exists("defaults.param") mav_ftp.cmd_getparams(["params.param", "defaults.param"]) - ret = mav_ftp.process_ftp_reply('OpenFileRO', timeout=500) + ret = mav_ftp.process_ftp_reply("OpenFileRO", timeout=500) ret.display_message() - get_list_dir(mav_ftp, '/APM/LOGS') + get_list_dir(mav_ftp, "/APM/LOGS") - #delete_local_file_if_exists("LASTLOG.TXT") + # delete_local_file_if_exists("LASTLOG.TXT") delete_local_file_if_exists("LASTLOG.BIN") - #get_file(mav_ftp, '/APM/LOGS/LASTLOG.TXT', 'LASTLOG.TXT') + # get_file(mav_ftp, '/APM/LOGS/LASTLOG.TXT', 'LASTLOG.TXT') - get_list_dir(mav_ftp, '/APM/LOGS') + get_list_dir(mav_ftp, "/APM/LOGS") - #get_file(mav_ftp, '/APM/LOGS/LASTLOG.TXT', 'LASTLOG2.TXT') + # get_file(mav_ftp, '/APM/LOGS/LASTLOG.TXT', 'LASTLOG2.TXT') get_last_log(mav_ftp) @@ -253,8 +259,8 @@ def main(): remove_directory(mav_ftp, "test_dir") create_directory(mav_ftp, "test_dir2") - remote_directory = '/APM/Scripts' - #create_directory(mav_ftp, remote_directory) + remote_directory = "/APM/Scripts" + # create_directory(mav_ftp, remote_directory) url = "https://discuss.ardupilot.org/uploads/short-url/4pyrl7PcfqiMEaRItUhljuAqLSs.lua" local_filename = "copter-magfit-helper.lua" @@ -264,8 +270,7 @@ def main(): upload_script(mav_ftp, remote_directory, local_filename, 5) - url = "https://raw.githubusercontent.com/ArduPilot/ardupilot/Copter-4.5/libraries/AP_Scripting/applets/" \ - "VTOL-quicktune.lua" + url = "https://raw.githubusercontent.com/ArduPilot/ardupilot/Copter-4.5/libraries/AP_Scripting/applets/VTOL-quicktune.lua" local_filename = "VTOL-quicktune.lua" if not os.path.exists(local_filename): diff --git a/MethodicConfigurator/middleware_template_overview.py b/MethodicConfigurator/middleware_template_overview.py index 5e19908..7b64c40 100644 --- a/MethodicConfigurator/middleware_template_overview.py +++ b/MethodicConfigurator/middleware_template_overview.py @@ -1,12 +1,13 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" + class TemplateOverview: # pylint: disable=too-many-instance-attributes """ @@ -17,32 +18,34 @@ class TemplateOverview: # pylint: disable=too-many-instance-attributes ESCs, propellers, and GNSS Receiver, along with their specifications. The class facilitates easy access to these attributes, enabling the GUI to display and select the templates in a structured format. """ + def __init__(self, components_data: dict): # The declaration order of these parameters determines the column order in the GUI - self.fc_manufacturer = components_data.get('Flight Controller', {}).get('Product', {}).get('Manufacturer', '') - self.fc_model = components_data.get('Flight Controller', {}).get('Product', {}).get('Model', '') - self.tow_max_kg = components_data.get('Frame', {}).get('Specifications', {}).get('TOW max Kg', '') - self.prop_diameter_inches = components_data.get('Propellers', {}).get('Specifications', {}).get('Diameter_inches', '') - self.rc_protocol = components_data.get('RC Receiver', {}).get('FC Connection', {}).get('Protocol', '') - self.telemetry_model = components_data.get('Telemetry', {}).get('Product', {}).get('Model', '') - self.esc_protocol = components_data.get('ESC', {}).get('FC Connection', {}).get('Protocol', '') - self.gnss_model = components_data.get('GNSS Receiver', {}).get('Product', {}).get('Model', '') - self.gnss_connection = components_data.get('GNSS Receiver', {}).get('FC Connection', {}).get('Type', '') + self.fc_manufacturer = components_data.get("Flight Controller", {}).get("Product", {}).get("Manufacturer", "") + self.fc_model = components_data.get("Flight Controller", {}).get("Product", {}).get("Model", "") + self.tow_max_kg = components_data.get("Frame", {}).get("Specifications", {}).get("TOW max Kg", "") + self.prop_diameter_inches = components_data.get("Propellers", {}).get("Specifications", {}).get("Diameter_inches", "") + self.rc_protocol = components_data.get("RC Receiver", {}).get("FC Connection", {}).get("Protocol", "") + self.telemetry_model = components_data.get("Telemetry", {}).get("Product", {}).get("Model", "") + self.esc_protocol = components_data.get("ESC", {}).get("FC Connection", {}).get("Protocol", "") + self.gnss_model = components_data.get("GNSS Receiver", {}).get("Product", {}).get("Model", "") + self.gnss_connection = components_data.get("GNSS Receiver", {}).get("FC Connection", {}).get("Type", "") @staticmethod def columns(): # Must match the order in the __init__() function above - return ("Template path", - "FC\nManufacturer", - "FC\nModel", - "TOW Max\n[KG]", - "Prop Diameter\n[inches]", - "RC\nProtocol", - "Telemetry\nModel", - "ESC\nProtocol", - "GNSS\nModel", - "GNSS\nConnection", - ) + return ( + "Template path", + "FC\nManufacturer", + "FC\nModel", + "TOW Max\n[KG]", + "Prop Diameter\n[inches]", + "RC\nProtocol", + "Telemetry\nModel", + "ESC\nProtocol", + "GNSS\nModel", + "GNSS\nConnection", + ) def attributes(self): return self.__dict__.keys() diff --git a/MethodicConfigurator/param_pid_adjustment_update.py b/MethodicConfigurator/param_pid_adjustment_update.py index d95bcbd..82f9cec 100755 --- a/MethodicConfigurator/param_pid_adjustment_update.py +++ b/MethodicConfigurator/param_pid_adjustment_update.py @@ -1,6 +1,6 @@ #!/usr/bin/python3 -''' +""" This script updates the PID adjustment parameters to be factor of the corresponding autotuned or optimized parameters. Usage: @@ -11,22 +11,23 @@ SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" -import os import argparse -import subprocess -from typing import List, Dict +import os import re +import subprocess +from typing import Dict, List, Optional -PARAM_NAME_REGEX = r'^[A-Z][A-Z_0-9]*$' +PARAM_NAME_REGEX = r"^[A-Z][A-Z_0-9]*$" PARAM_NAME_MAX_LEN = 16 -VERSION = '1.0' +VERSION = "1.0" def parse_arguments(): - parser = argparse.ArgumentParser(formatter_class=argparse.RawDescriptionHelpFormatter, - description=""" + parser = argparse.ArgumentParser( + formatter_class=argparse.RawDescriptionHelpFormatter, + description=""" Updates PID adjustment parameters values based on the given ADJUSTMENT_FACTOR argument. It loads three sets of parameters from files in the DIRECTORY directory: @@ -36,22 +37,33 @@ def parse_arguments(): It calculates the PID adjustment parameter values based on the ADJUSTMENT_FACTOR argument. It updates the intermediate parameter file 16_pid_adjustment.param with parameter comments explaining how their new value relates to the default parameter value. -""") - parser.add_argument("-d", "--directory", - required=True, - help="The directory where the parameter files are located.", - ) - parser.add_argument("-a", "--adjustment_factor", - type=ranged_type(float, 0.1, 0.8), default=0.5, - help="The adjustment factor to apply to the optimized parameters. " - "Must be in the interval 0.1 to 0.8. Defaults to 0.5.", - ) - parser.add_argument('-v', '--version', action='version', version=f'%(prog)s {VERSION}', - help='Display version information and exit.', - ) - parser.add_argument("optimized_param_file", - help="The name of the optimized parameter file.", - ) +""", + ) + parser.add_argument( + "-d", + "--directory", + required=True, + help="The directory where the parameter files are located.", + ) + parser.add_argument( + "-a", + "--adjustment_factor", + type=ranged_type(float, 0.1, 0.8), + default=0.5, + help="The adjustment factor to apply to the optimized parameters. " + "Must be in the interval 0.1 to 0.8. Defaults to 0.5.", + ) + parser.add_argument( + "-v", + "--version", + action="version", + version=f"%(prog)s {VERSION}", + help="Display version information and exit.", + ) + parser.add_argument( + "optimized_param_file", + help="The name of the optimized parameter file.", + ) args = parser.parse_args() return args @@ -65,14 +77,16 @@ def ranged_type(value_type, min_value, max_value): min_value - minimum acceptable argument value max_value - maximum acceptable argument value """ + def range_checker(arg: str): try: f = value_type(arg) except ValueError as exc: - raise argparse.ArgumentTypeError(f'must be a valid {value_type}') from exc + raise argparse.ArgumentTypeError(f"must be a valid {value_type}") from exc if f < min_value or f > max_value: - raise argparse.ArgumentTypeError(f'must be within [{min_value}, {max_value}]') + raise argparse.ArgumentTypeError(f"must be within [{min_value}, {max_value}]") return f + # Return function handle to checking function return range_checker @@ -85,17 +99,18 @@ class Par: value (float): The value of the parameter. comment (str): An optional comment describing the parameter. """ - def __init__(self, value: float, comment: str = None): + + def __init__(self, value: float, comment: Optional[str] = None): self.value = value self.comment = comment @staticmethod - def load_param_file_into_dict(param_file: str) -> Dict[str, 'Par']: + def load_param_file_into_dict(param_file: str) -> Dict[str, "Par"]: parameter_dict = {} content = [] with open(param_file, encoding="utf-8") as f_handle: - for n, line in enumerate(f_handle, start=1): - line = line.strip() + 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("#"): @@ -125,12 +140,12 @@ def load_param_file_into_dict(param_file: str) -> Dict[str, 'Par']: return parameter_dict, content @staticmethod - def export_to_param(param_dict: Dict[str, 'Par'], filename_out: str, content_header: List[str] = None) -> None: + 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') + 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: @@ -189,8 +204,10 @@ def update_pid_adjustment_params(directory: str, optimized_param_file: str, adju coef = 1.0 param_value.value = 0 # if the default is zero, let it stay at zero, it is safer # explain how the new value relates to the default parameter value - param_value.comment = f" = {format(coef, '.6f').rstrip('0').rstrip('.')} * (" \ - f"{format(default_params_dict[param_name].value, '.6f').rstrip('0').rstrip('.')} default)" + param_value.comment = ( + f" = {format(coef, '.6f').rstrip('0').rstrip('.')} * (" + f"{format(default_params_dict[param_name].value, '.6f').rstrip('0').rstrip('.')} default)" + ) return pid_adjustment_params_dict, pid_adjustment_file_path, content[0:7] @@ -199,11 +216,12 @@ def main(): args = parse_arguments() # calculate the parameter values and their comments pid_adjustment_params_dict, pid_adjustment_file_path, content_header = update_pid_adjustment_params( - args.directory, args.optimized_param_file, args.adjustment_factor) + 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) + subprocess.run(["./annotate_params.py", os.path.join(args.directory, "16_pid_adjustment.param")], check=True) if __name__ == "__main__": diff --git a/MethodicConfigurator/tempcal_imu.py b/MethodicConfigurator/tempcal_imu.py index b8178dd..803a627 100644 --- a/MethodicConfigurator/tempcal_imu.py +++ b/MethodicConfigurator/tempcal_imu.py @@ -1,5 +1,5 @@ #!/usr/bin/env python3 -''' +""" Create temperature calibration parameters for IMUs based on log data. The original (python2) version of this file is part of the Ardupilot project. @@ -10,12 +10,12 @@ SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" import math +import os import re import sys -import os from argparse import ArgumentParser import numpy as np @@ -36,18 +36,19 @@ # use exponential notation SCALE_FACTOR = 1.0e6 -AXES = ['X', 'Y', 'Z'] -AXEST = ['X', 'Y', 'Z', 'T', 'time'] +AXES = ["X", "Y", "Z"] +AXEST = ["X", "Y", "Z", "T", "time"] class Coefficients: # pylint: disable=too-many-instance-attributes - '''class representing a set of coefficients''' + """class representing a set of coefficients""" + def __init__(self): self.acoef = {} self.gcoef = {} - self.enable = [0]*3 - self.tmin = [-100]*3 - self.tmax = [-100]*3 + self.enable = [0] * 3 + self.tmin = [-100] * 3 + self.tmax = [-100] * 3 self.gtcal = {} self.atcal = {} self.gofs = {} @@ -67,15 +68,15 @@ def set_acoeff(self, imu, axis, order, value): if imu not in self.acoef: self.acoef[imu] = {} if axis not in self.acoef[imu]: - self.acoef[imu][axis] = [0]*4 - self.acoef[imu][axis][POLY_ORDER-order] = value + self.acoef[imu][axis] = [0] * 4 + self.acoef[imu][axis][POLY_ORDER - order] = value def set_gcoeff(self, imu, axis, order, value): if imu not in self.gcoef: self.gcoef[imu] = {} if axis not in self.gcoef[imu]: - self.gcoef[imu][axis] = [0]*4 - self.gcoef[imu][axis][POLY_ORDER-order] = value + self.gcoef[imu][axis] = [0] * 4 + self.gcoef[imu][axis][POLY_ORDER - order] = value def set_aoffset(self, imu, axis, value): if imu not in self.aofs: @@ -103,7 +104,7 @@ def set_enable(self, imu, value): self.enable[imu] = value def correction(self, coeff, imu, temperature, axis, cal_temp): # pylint: disable=too-many-arguments - '''calculate correction from temperature calibration from log data using parameters''' + """calculate correction from temperature calibration from log data using parameters""" if self.enable[imu] != 1.0: return 0.0 if cal_temp < -80: @@ -116,37 +117,42 @@ def correction(self, coeff, imu, temperature, axis, cal_temp): # pylint: disabl return poly(cal_temp - TEMP_REF) - poly(temperature - TEMP_REF) def correction_accel(self, imu, temperature): - '''calculate accel correction from temperature calibration from - log data using parameters''' + """calculate accel correction from temperature calibration from + log data using parameters""" cal_temp = self.atcal.get(imu, TEMP_REF) - return Vector3(self.correction(self.acoef[imu], imu, temperature, 'X', cal_temp), - self.correction(self.acoef[imu], imu, temperature, 'Y', cal_temp), - self.correction(self.acoef[imu], imu, temperature, 'Z', cal_temp)) + return Vector3( + self.correction(self.acoef[imu], imu, temperature, "X", cal_temp), + self.correction(self.acoef[imu], imu, temperature, "Y", cal_temp), + self.correction(self.acoef[imu], imu, temperature, "Z", cal_temp), + ) def correction_gyro(self, imu, temperature): - '''calculate gyro correction from temperature calibration from - log data using parameters''' + """calculate gyro correction from temperature calibration from + log data using parameters""" cal_temp = self.gtcal.get(imu, TEMP_REF) - return Vector3(self.correction(self.gcoef[imu], imu, temperature, 'X', cal_temp), - self.correction(self.gcoef[imu], imu, temperature, 'Y', cal_temp), - self.correction(self.gcoef[imu], imu, temperature, 'Z', cal_temp)) + return Vector3( + self.correction(self.gcoef[imu], imu, temperature, "X", cal_temp), + self.correction(self.gcoef[imu], imu, temperature, "Y", cal_temp), + self.correction(self.gcoef[imu], imu, temperature, "Z", cal_temp), + ) def param_string(self, imu): - params = '' - params += f'INS_TCAL{imu+1}_ENABLE 1\n' - params += f'INS_TCAL{imu+1}_TMIN {self.tmin[imu]:.1f}\n' - params += f'INS_TCAL{imu+1}_TMAX {self.tmax[imu]:.1f}\n' + params = "" + params += f"INS_TCAL{imu+1}_ENABLE 1\n" + params += f"INS_TCAL{imu+1}_TMIN {self.tmin[imu]:.1f}\n" + params += f"INS_TCAL{imu+1}_TMAX {self.tmax[imu]:.1f}\n" for p in range(POLY_ORDER): for axis in AXES: - params += f'INS_TCAL{imu+1}_ACC{p+1}_{axis} {self.acoef[imu][axis][POLY_ORDER-(p+1)]*SCALE_FACTOR:.9f}\n' + params += f"INS_TCAL{imu+1}_ACC{p+1}_{axis} {self.acoef[imu][axis][POLY_ORDER-(p+1)]*SCALE_FACTOR:.9f}\n" for p in range(POLY_ORDER): for axis in AXES: - params += f'INS_TCAL{imu+1}_GYR{p+1}_{axis} {self.gcoef[imu][axis][POLY_ORDER-(p+1)]*SCALE_FACTOR:.9f}\n' + params += f"INS_TCAL{imu+1}_GYR{p+1}_{axis} {self.gcoef[imu][axis][POLY_ORDER-(p+1)]*SCALE_FACTOR:.9f}\n" return params class OnlineIMUfit: - '''implement the online learning used in ArduPilot''' + """implement the online learning used in ArduPilot""" + def __init__(self): self.porder = None self.mat = None @@ -155,14 +161,14 @@ def __init__(self): def update(self, x, y): temp = 1.0 - for i in range(2*(self.porder - 1), -1, -1): + for i in range(2 * (self.porder - 1), -1, -1): k = 0 if (i < self.porder) else (i - self.porder + 1) - for j in range(i - k, k-1, -1): - self.mat[j][i-j] += temp + for j in range(i - k, k - 1, -1): + self.mat[j][i - j] += temp temp *= x temp = 1.0 - for i in range(self.porder-1, -1, -1): + for i in range(self.porder - 1, -1, -1): self.vec[i] += y * temp temp *= x @@ -191,12 +197,13 @@ class IMUData: This class provides methods to add acceleration and gyroscope data, apply moving average filters, and retrieve data for specific IMUs and temperatures. """ + def __init__(self): self.accel = {} self.gyro = {} def IMUs(self): - '''return list of IMUs''' + """return list of IMUs""" if len(self.accel.keys()) != len(self.gyro.keys()): print("accel and gyro data doesn't match") sys.exit(1) @@ -207,33 +214,33 @@ def add_accel(self, imu, temperature, time, value): self.accel[imu] = {} for axis in AXEST: self.accel[imu][axis] = np.zeros(0, dtype=float) - self.accel[imu]['T'] = np.append(self.accel[imu]['T'], temperature) - self.accel[imu]['X'] = np.append(self.accel[imu]['X'], value.x) - self.accel[imu]['Y'] = np.append(self.accel[imu]['Y'], value.y) - self.accel[imu]['Z'] = np.append(self.accel[imu]['Z'], value.z) - self.accel[imu]['time'] = np.append(self.accel[imu]['time'], time) + self.accel[imu]["T"] = np.append(self.accel[imu]["T"], temperature) + self.accel[imu]["X"] = np.append(self.accel[imu]["X"], value.x) + self.accel[imu]["Y"] = np.append(self.accel[imu]["Y"], value.y) + self.accel[imu]["Z"] = np.append(self.accel[imu]["Z"], value.z) + self.accel[imu]["time"] = np.append(self.accel[imu]["time"], time) def add_gyro(self, imu, temperature, time, value): if imu not in self.gyro: self.gyro[imu] = {} for axis in AXEST: self.gyro[imu][axis] = np.zeros(0, dtype=float) - self.gyro[imu]['T'] = np.append(self.gyro[imu]['T'], temperature) - self.gyro[imu]['X'] = np.append(self.gyro[imu]['X'], value.x) - self.gyro[imu]['Y'] = np.append(self.gyro[imu]['Y'], value.y) - self.gyro[imu]['Z'] = np.append(self.gyro[imu]['Z'], value.z) - self.gyro[imu]['time'] = np.append(self.gyro[imu]['time'], time) + self.gyro[imu]["T"] = np.append(self.gyro[imu]["T"], temperature) + self.gyro[imu]["X"] = np.append(self.gyro[imu]["X"], value.x) + self.gyro[imu]["Y"] = np.append(self.gyro[imu]["Y"], value.y) + self.gyro[imu]["Z"] = np.append(self.gyro[imu]["Z"], value.z) + self.gyro[imu]["time"] = np.append(self.gyro[imu]["time"], time) def moving_average(self, data, w): - '''apply a moving average filter over a window of width w''' + """apply a moving average filter over a window of width w""" ret = np.cumsum(data) ret[w:] = ret[w:] - ret[:-w] - return ret[w - 1:] / w + return ret[w - 1 :] / w def FilterArray(self, data, width_s): - '''apply moving average filter of width width_s seconds''' - nseconds = data['time'][-1] - data['time'][0] - nsamples = len(data['time']) + """apply moving average filter of width width_s seconds""" + nseconds = data["time"][-1] - data["time"][0] + nsamples = len(data["time"]) window = int(nsamples / nseconds) * width_s if window > 1: for axis in AXEST: @@ -241,33 +248,33 @@ def FilterArray(self, data, width_s): return data def Filter(self, width_s): - '''apply moving average filter of width width_s seconds''' + """apply moving average filter of width width_s seconds""" for imu in self.IMUs(): self.accel[imu] = self.FilterArray(self.accel[imu], width_s) self.gyro[imu] = self.FilterArray(self.gyro[imu], width_s) def accel_at_temp(self, imu, axis, temperature): - '''return the accel value closest to the given temperature''' - if temperature < self.accel[imu]['T'][0]: + """return the accel value closest to the given temperature""" + if temperature < self.accel[imu]["T"][0]: return self.accel[imu][axis][0] - for i in range(len(self.accel[imu]['T'])-1): - if self.accel[imu]['T'][i] <= temperature <= self.accel[imu]['T'][i+1]: + for i in range(len(self.accel[imu]["T"]) - 1): + if self.accel[imu]["T"][i] <= temperature <= self.accel[imu]["T"][i + 1]: v1 = self.accel[imu][axis][i] - v2 = self.accel[imu][axis][i+1] - p = (temperature - self.accel[imu]['T'][i]) / (self.accel[imu]['T'][i+1]-self.accel[imu]['T'][i]) - return v1 + (v2-v1) * p + v2 = self.accel[imu][axis][i + 1] + p = (temperature - self.accel[imu]["T"][i]) / (self.accel[imu]["T"][i + 1] - self.accel[imu]["T"][i]) + return v1 + (v2 - v1) * p return self.accel[imu][axis][-1] def gyro_at_temp(self, imu, axis, temperature): - '''return the gyro value closest to the given temperature''' - if temperature < self.gyro[imu]['T'][0]: + """return the gyro value closest to the given temperature""" + if temperature < self.gyro[imu]["T"][0]: return self.gyro[imu][axis][0] - for i in range(len(self.gyro[imu]['T'])-1): - if self.gyro[imu]['T'][i] <= temperature <= self.gyro[imu]['T'][i+1]: + for i in range(len(self.gyro[imu]["T"]) - 1): + if self.gyro[imu]["T"][i] <= temperature <= self.gyro[imu]["T"][i + 1]: v1 = self.gyro[imu][axis][i] - v2 = self.gyro[imu][axis][i+1] - p = (temperature - self.gyro[imu]['T'][i]) / (self.gyro[imu]['T'][i+1]-self.gyro[imu]['T'][i]) - return v1 + (v2-v1) * p + v2 = self.gyro[imu][axis][i + 1] + p = (temperature - self.gyro[imu]["T"][i]) / (self.gyro[imu]["T"][i + 1] - self.gyro[imu]["T"][i]) + return v1 + (v2 - v1) * p return self.gyro[imu][axis][-1] @@ -278,11 +285,17 @@ def constrain(value, minv, maxv): return value -def IMUfit(logfile, outfile, # pylint: disable=too-many-locals, too-many-branches, too-many-statements, too-many-arguments - no_graph, log_parm, - online, tclr, figpath, - progress_callback): - '''find IMU calibration parameters from a log file''' +def IMUfit( # pylint: disable=too-many-locals, too-many-branches, too-many-statements, too-many-arguments + logfile, + outfile, + no_graph, + log_parm, + online, + tclr, + figpath, + progress_callback, +): + """find IMU calibration parameters from a log file""" print(f"Processing log {logfile}") mlog = mavutil.mavlink_connection(logfile, progress_callback=progress_callback) @@ -294,9 +307,9 @@ def IMUfit(logfile, outfile, # pylint: disable=too-many-locals, too-many-bra stop_capture = [False] * 3 if tclr: - messages = ['PARM', 'TCLR'] + messages = ["PARM", "TCLR"] else: - messages = ['PARM', 'IMU'] + messages = ["PARM", "IMU"] # Pre-compile regular expressions used frequently inside the loop enable_pattern = re.compile(r"^INS_TCAL(\d)_ENABLE$") @@ -324,16 +337,16 @@ def IMUfit(logfile, outfile, # pylint: disable=too-many-locals, too-many-bra msgcnt += 1 new_pct = (100 * msgcnt) // total_msgs if new_pct != pct: - progress_callback(100+new_pct) + progress_callback(100 + new_pct) pct = new_pct msg_type = msg.get_type() - if msg_type == 'PARM': + if msg_type == "PARM": # build up the old coefficients so we can remove the impact of # existing coefficients from the data m = enable_pattern.match(msg.Name) if m: - imu = int(m.group(1))-1 + imu = int(m.group(1)) - 1 if stop_capture[imu]: continue if msg.Value == 1 and c.enable[imu] == 2: @@ -348,41 +361,41 @@ def IMUfit(logfile, outfile, # pylint: disable=too-many-locals, too-many-bra continue m = coeff_pattern.match(msg.Name) if m: - imu = int(m.group(1))-1 + imu = int(m.group(1)) - 1 stype = m.group(2) p = int(m.group(3)) axis = m.group(4) if stop_capture[imu]: continue - if stype == 'ACC': - c.set_acoeff(imu, axis, p, msg.Value/SCALE_FACTOR) - if stype == 'GYR': - c.set_gcoeff(imu, axis, p, msg.Value/SCALE_FACTOR) + if stype == "ACC": + c.set_acoeff(imu, axis, p, msg.Value / SCALE_FACTOR) + if stype == "GYR": + c.set_gcoeff(imu, axis, p, msg.Value / SCALE_FACTOR) continue m = tmin_pattern.match(msg.Name) if m: - imu = int(m.group(1))-1 + imu = int(m.group(1)) - 1 if stop_capture[imu]: continue c.set_tmin(imu, msg.Value) continue m = tmax_pattern.match(msg.Name) if m: - imu = int(m.group(1))-1 + imu = int(m.group(1)) - 1 if stop_capture[imu]: continue c.set_tmax(imu, msg.Value) continue m = gyr_caltemp_pattern.match(msg.Name) if m: - imu = int(m.group(1))-1 + imu = int(m.group(1)) - 1 if stop_capture[imu]: continue c.set_gyro_tcal(imu, msg.Value) continue m = acc_caltemp_pattern.match(msg.Name) if m: - imu = int(m.group(1))-1 + imu = int(m.group(1)) - 1 if stop_capture[imu]: continue c.set_accel_tcal(imu, msg.Value) @@ -393,37 +406,37 @@ def IMUfit(logfile, outfile, # pylint: disable=too-many-locals, too-many-bra if m.group(2) == "": imu = 0 else: - imu = int(m.group(2))-1 + imu = int(m.group(2)) - 1 axis = m.group(3) if stop_capture[imu]: continue - if stype == 'ACC': + if stype == "ACC": c.set_aoffset(imu, axis, msg.Value) - if stype == 'GYR': + if stype == "GYR": c.set_goffset(imu, axis, msg.Value) continue - if msg.Name == 'AHRS_ORIENTATION': + if msg.Name == "AHRS_ORIENTATION": orientation = int(msg.Value) print(f"Using orientation {orientation}") continue - if msg_type == 'TCLR' and tclr: + if msg_type == "TCLR" and tclr: imu = msg.I T = msg.Temp if msg.SType == 0: # accel acc = Vector3(msg.X, msg.Y, msg.Z) - time = msg.TimeUS*1.0e-6 + time = msg.TimeUS * 1.0e-6 data.add_accel(imu, T, time, acc) elif msg.SType == 1: # gyro gyr = Vector3(msg.X, msg.Y, msg.Z) - time = msg.TimeUS*1.0e-6 + time = msg.TimeUS * 1.0e-6 data.add_gyro(imu, T, time, gyr) continue - if msg_type == 'IMU' and not tclr: + if msg_type == "IMU" and not tclr: imu = msg.I if stop_capture[imu]: @@ -445,7 +458,7 @@ def IMUfit(logfile, outfile, # pylint: disable=too-many-locals, too-many-bra acc -= c.correction_accel(imu, T) gyr -= c.correction_gyro(imu, T) - time = msg.TimeUS*1.0e-6 + time = msg.TimeUS * 1.0e-6 data.add_accel(imu, T, time, acc) data.add_gyro(imu, T, time, gyr) @@ -479,6 +492,7 @@ def IMUfit(logfile, outfile, # pylint: disable=too-many-locals, too-many-bra pyplot.show() + def generate_calibration_file(outfile, online, progress_callback, data, c): # pylint: disable=too-many-locals clog = c c = Coefficients() @@ -487,10 +501,10 @@ def generate_calibration_file(outfile, online, progress_callback, data, c): # p progress = 220 progress_callback(progress) progress_delta = 60 / (len(data.IMUs()) * len(AXES)) - with open(outfile, "w", encoding='utf-8') as calfile: + with open(outfile, "w", encoding="utf-8") as calfile: for imu in data.IMUs(): - tmin = np.amin(data.accel[imu]['T']) - tmax = np.amax(data.accel[imu]['T']) + tmin = np.amin(data.accel[imu]["T"]) + tmax = np.amax(data.accel[imu]["T"]) c.set_tmin(imu, tmin) c.set_tmax(imu, tmax) @@ -498,19 +512,19 @@ def generate_calibration_file(outfile, online, progress_callback, data, c): # p for axis in AXES: if online: fit = OnlineIMUfit() - trel = data.accel[imu]['T'] - TEMP_REF + trel = data.accel[imu]["T"] - TEMP_REF ofs = data.accel_at_temp(imu, axis, clog.atcal[imu]) c.set_accel_poly(imu, axis, fit.polyfit(trel, data.accel[imu][axis] - ofs, POLY_ORDER)) - trel = data.gyro[imu]['T'] - TEMP_REF + trel = data.gyro[imu]["T"] - TEMP_REF c.set_gyro_poly(imu, axis, fit.polyfit(trel, data.gyro[imu][axis], POLY_ORDER)) else: - trel = data.accel[imu]['T'] - TEMP_REF + trel = data.accel[imu]["T"] - TEMP_REF if imu in clog.atcal: ofs = data.accel_at_temp(imu, axis, clog.atcal[imu]) else: ofs = np.mean(data.accel[imu][axis]) c.set_accel_poly(imu, axis, np.polyfit(trel, data.accel[imu][axis] - ofs, POLY_ORDER)) - trel = data.gyro[imu]['T'] - TEMP_REF + trel = data.gyro[imu]["T"] - TEMP_REF c.set_gyro_poly(imu, axis, np.polyfit(trel, data.gyro[imu][axis], POLY_ORDER)) if progress_callback: progress += progress_delta @@ -523,6 +537,7 @@ def generate_calibration_file(outfile, online, progress_callback, data, c): # p print(f"Calibration written to {outfile}") return c, clog + def generate_tempcal_gyro_figures(log_parm, figpath, data, c, clog, num_imus): # pylint: disable=too-many-arguments _fig, axs = pyplot.subplots(len(data.IMUs()), 1, sharex=True) if num_imus == 1: @@ -531,29 +546,31 @@ def generate_tempcal_gyro_figures(log_parm, figpath, data, c, clog, num_imus): for imu in data.IMUs(): scale = math.degrees(1) for axis in AXES: - axs[imu].plot(data.gyro[imu]['time'], data.gyro[imu][axis]*scale, label=f'Uncorrected {axis}') + axs[imu].plot(data.gyro[imu]["time"], data.gyro[imu][axis] * scale, label=f"Uncorrected {axis}") for axis in AXES: poly = np.poly1d(c.gcoef[imu][axis]) - trel = data.gyro[imu]['T'] - TEMP_REF + trel = data.gyro[imu]["T"] - TEMP_REF correction = poly(trel) - axs[imu].plot(data.gyro[imu]['time'], (data.gyro[imu][axis] - correction)*scale, label=f'Corrected {axis}') + axs[imu].plot(data.gyro[imu]["time"], (data.gyro[imu][axis] - correction) * scale, label=f"Corrected {axis}") if log_parm: for axis in AXES: if clog.enable[imu] == 0.0: print(f"IMU[{imu}] disabled in log parms") continue poly = np.poly1d(clog.gcoef[imu][axis]) - correction = poly(data.gyro[imu]['T'] - TEMP_REF) - poly(clog.gtcal[imu] - TEMP_REF) + clog.gofs[imu][axis] - axs[imu].plot(data.gyro[imu]['time'], (data.gyro[imu][axis] - correction)*scale, - label=f'Corrected {axis} (log parm)') + correction = poly(data.gyro[imu]["T"] - TEMP_REF) - poly(clog.gtcal[imu] - TEMP_REF) + clog.gofs[imu][axis] + axs[imu].plot( + data.gyro[imu]["time"], (data.gyro[imu][axis] - correction) * scale, label=f"Corrected {axis} (log parm)" + ) ax2 = axs[imu].twinx() - ax2.plot(data.gyro[imu]['time'], data.gyro[imu]['T'], label='Temperature(C)', color='black') - ax2.legend(loc='upper right') - axs[imu].legend(loc='upper left') - axs[imu].set_title(f'IMU[{imu}] Gyro (deg/s)') + ax2.plot(data.gyro[imu]["time"], data.gyro[imu]["T"], label="Temperature(C)", color="black") + ax2.legend(loc="upper right") + axs[imu].legend(loc="upper left") + axs[imu].set_title(f"IMU[{imu}] Gyro (deg/s)") if figpath: - _fig.savefig(os.path.join(figpath, 'tempcal_gyro.png')) + _fig.savefig(os.path.join(figpath, "tempcal_gyro.png")) + def generate_tempcal_accel_figures(log_parm, figpath, data, c, clog, num_imus): # pylint: disable=too-many-arguments _fig, axs = pyplot.subplots(num_imus, 1, sharex=True) @@ -563,14 +580,13 @@ def generate_tempcal_accel_figures(log_parm, figpath, data, c, clog, num_imus): for imu in data.IMUs(): for axis in AXES: ofs = data.accel_at_temp(imu, axis, clog.atcal.get(imu, TEMP_REF)) - axs[imu].plot(data.accel[imu]['time'], data.accel[imu][axis] - ofs, label=f'Uncorrected {axis}') + axs[imu].plot(data.accel[imu]["time"], data.accel[imu][axis] - ofs, label=f"Uncorrected {axis}") for axis in AXES: poly = np.poly1d(c.acoef[imu][axis]) - trel = data.accel[imu]['T'] - TEMP_REF + trel = data.accel[imu]["T"] - TEMP_REF correction = poly(trel) ofs = data.accel_at_temp(imu, axis, clog.atcal.get(imu, TEMP_REF)) - axs[imu].plot(data.accel[imu]['time'], (data.accel[imu][axis] - ofs) - correction, - label=f'Corrected {axis}') + axs[imu].plot(data.accel[imu]["time"], (data.accel[imu][axis] - ofs) - correction, label=f"Corrected {axis}") if log_parm: for axis in AXES: if clog.enable[imu] == 0.0: @@ -578,31 +594,31 @@ def generate_tempcal_accel_figures(log_parm, figpath, data, c, clog, num_imus): continue poly = np.poly1d(clog.acoef[imu][axis]) ofs = data.accel_at_temp(imu, axis, clog.atcal[imu]) - correction = poly(data.accel[imu]['T'] - TEMP_REF) - poly(clog.atcal[imu] - TEMP_REF) - axs[imu].plot(data.accel[imu]['time'], (data.accel[imu][axis] - ofs) - correction, - label=f'Corrected {axis} (log parm)') + correction = poly(data.accel[imu]["T"] - TEMP_REF) - poly(clog.atcal[imu] - TEMP_REF) + axs[imu].plot( + data.accel[imu]["time"], (data.accel[imu][axis] - ofs) - correction, label=f"Corrected {axis} (log parm)" + ) ax2 = axs[imu].twinx() - ax2.plot(data.accel[imu]['time'], data.accel[imu]['T'], label='Temperature(C)', color='black') - ax2.legend(loc='upper right') - axs[imu].legend(loc='upper left') - axs[imu].set_title(f'IMU[{imu}] Accel (m/s^2)') + ax2.plot(data.accel[imu]["time"], data.accel[imu]["T"], label="Temperature(C)", color="black") + ax2.legend(loc="upper right") + axs[imu].legend(loc="upper left") + axs[imu].set_title(f"IMU[{imu}] Accel (m/s^2)") if figpath: - _fig.savefig(os.path.join(figpath, 'tempcal_acc.png')) + _fig.savefig(os.path.join(figpath, "tempcal_acc.png")) def main(): parser = ArgumentParser(description=__doc__) - parser.add_argument("--outfile", default="tcal.parm", - help='set output file') - parser.add_argument("--no-graph", action='store_true', default=False, - help='disable graph display') - parser.add_argument("--log-parm", action='store_true', default=False, - help='show corrections using coefficients from log file') - parser.add_argument("--online", action='store_true', default=False, - help='use online polynomial fitting') - parser.add_argument("--tclr", action='store_true', default=False, - help='use TCLR messages from log instead of IMU messages') + parser.add_argument("--outfile", default="tcal.parm", help="set output file") + parser.add_argument("--no-graph", action="store_true", default=False, help="disable graph display") + parser.add_argument( + "--log-parm", action="store_true", default=False, help="show corrections using coefficients from log file" + ) + parser.add_argument("--online", action="store_true", default=False, help="use online polynomial fitting") + parser.add_argument( + "--tclr", action="store_true", default=False, help="use TCLR messages from log instead of IMU messages" + ) parser.add_argument("log", metavar="LOG") args = parser.parse_args() diff --git a/MethodicConfigurator/version.py b/MethodicConfigurator/version.py index 71fc3d1..e587afe 100644 --- a/MethodicConfigurator/version.py +++ b/MethodicConfigurator/version.py @@ -1,11 +1,11 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" -VERSION = '0.9.9' +VERSION = "0.9.9" diff --git a/copy_magfit_pdef_to_template_dirs.py b/copy_magfit_pdef_to_template_dirs.py index d2d2ecf..61346c5 100755 --- a/copy_magfit_pdef_to_template_dirs.py +++ b/copy_magfit_pdef_to_template_dirs.py @@ -1,20 +1,20 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" import os import shutil import sys # Define the source directory and the file to be copied -BASE_TARGET_DIR = 'vehicle_templates/' -FILE_TO_COPY = '24_inflight_magnetometer_fit_setup.pdef.xml' +BASE_TARGET_DIR = "vehicle_templates/" +FILE_TO_COPY = "24_inflight_magnetometer_fit_setup.pdef.xml" # Ensure the base target directory exists if not os.path.exists(BASE_TARGET_DIR): @@ -22,7 +22,7 @@ sys.exit(1) # Ensure the file to be copied exists -source_file_path = os.path.join('.', FILE_TO_COPY) +source_file_path = os.path.join(".", FILE_TO_COPY) if not os.path.exists(source_file_path): print(f"Error: File {source_file_path} does not exist.") sys.exit(1) diff --git a/copy_param_files.py b/copy_param_files.py index 81c54a3..a4ac24a 100644 --- a/copy_param_files.py +++ b/copy_param_files.py @@ -1,12 +1,12 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" import os import shutil @@ -20,6 +20,7 @@ # Base directory for vehicle templates BASE_DIR = "vehicle_templates" + # Function to get all subdirectories excluding the source (do not copy onto itself) def get_subdirectories(base_dir, exclude_source=True): subdirs = [] @@ -31,6 +32,7 @@ def get_subdirectories(base_dir, exclude_source=True): subdirs.append(rel_dir) return subdirs + # Function to copy files def copy_files(source, target): for file in files_to_copy: @@ -41,7 +43,8 @@ def copy_files(source, target): shutil.copy2(source_path, target_path) print(f"Copied {file} to {target}") except Exception as e: # pylint: disable=broad-except - print(f"Error copying {file} to {target}: {str(e)}") + print(f"Error copying {file} to {target}: {e!s}") + # Get all ArduCopter subdirectories target_dirs = get_subdirectories(BASE_DIR) diff --git a/create_mo_files.py b/create_mo_files.py index c0a592b..746bf1a 100755 --- a/create_mo_files.py +++ b/create_mo_files.py @@ -1,35 +1,38 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" import os import subprocess + def process_locale_directory(locale_dir): """Process a single locale directory.""" - po_file = os.path.join(locale_dir, 'MethodicConfigurator.po') - mo_file = os.path.join(locale_dir, 'MethodicConfigurator.mo') + po_file = os.path.join(locale_dir, "MethodicConfigurator.po") + mo_file = os.path.join(locale_dir, "MethodicConfigurator.mo") try: # Run msgfmt command - cmd = ['msgfmt', '-o', mo_file, po_file] + cmd = ["msgfmt", "-o", mo_file, po_file] subprocess.run(cmd, check=True, capture_output=True, text=True) print(f"Successfully processed {locale_dir}") except subprocess.CalledProcessError as e: print(f"Error processing {locale_dir}: {e}") + def main(): # Walk through all locale directories - for root, dirs, _files in os.walk(os.path.join('MethodicConfigurator', 'locale')): - if 'LC_MESSAGES' in dirs: - locale_dir = os.path.join(root, 'LC_MESSAGES') + for root, dirs, _files in os.walk(os.path.join("MethodicConfigurator", "locale")): + if "LC_MESSAGES" in dirs: + locale_dir = os.path.join(root, "LC_MESSAGES") process_locale_directory(locale_dir) + if __name__ == "__main__": main() diff --git a/create_pot_file.py b/create_pot_file.py index 1cb8695..abc1ac3 100755 --- a/create_pot_file.py +++ b/create_pot_file.py @@ -1,46 +1,45 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" import os import subprocess + def extract_strings(directory, output_dir): file_paths = [] for root, _dirs, files in os.walk(directory): for file in files: - if file.endswith('.py'): + if file.endswith(".py"): file_path = os.path.join(root, file) # pylint: disable=too-many-boolean-expressions - if 'annotate_params' in file or \ - '__init__' in file or \ - 'backend_mavftp' in file or \ - 'extract_param_defaults' in file or \ - 'download_numbers.py' in file or \ - 'get_release_stats' in file or \ - 'mavftp_example' in file or \ - 'param_pid_adjustment_update' in file or \ - 'safe_eval' in file or \ - 'tempcal_imu' in file: - # pylint: enable=too-many-boolean-expressions + if ( + "annotate_params" in file + or "__init__" in file + or "backend_mavftp" in file + or "extract_param_defaults" in file + or "download_numbers.py" in file + or "get_release_stats" in file + or "mavftp_example" in file + or "param_pid_adjustment_update" in file + or "safe_eval" in file + or "tempcal_imu" in file + ): + # pylint: enable=too-many-boolean-expressions continue file_paths.append(file_path) # Construct the command - output_pot = os.path.join(output_dir, 'MethodicConfigurator.pot') - cmd = [ - 'pygettext3', - '--keyword=_', - f'--output={output_pot}' - ] + output_pot = os.path.join(output_dir, "MethodicConfigurator.pot") + cmd = ["pygettext3", "--keyword=_", f"--output={output_pot}"] cmd += file_paths try: @@ -50,15 +49,17 @@ def extract_strings(directory, output_dir): print(f"An error occurred while running pygettext3:\n{e}") raise - filenames = ' '.join(file_paths).replace(directory + os.pathsep, '') + filenames = " ".join(file_paths).replace(directory + os.pathsep, "") print(f"POT file created successfully for {filenames}") + def main(): - directory_to_scan = 'MethodicConfigurator' - output_directory = os.path.join(directory_to_scan, 'locale') + directory_to_scan = "MethodicConfigurator" + output_directory = os.path.join(directory_to_scan, "locale") extract_strings(directory_to_scan, output_directory) print(f"Internationalization strings extracted and saved to {output_directory}") + if __name__ == "__main__": main() diff --git a/credits/update_credits_licenses.py b/credits/update_credits_licenses.py index 1fec9ad..dbb39ee 100644 --- a/credits/update_credits_licenses.py +++ b/credits/update_credits_licenses.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 -''' +""" This script downloads the licenses of the direct and indirect dependencies of the project This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator @@ -8,11 +8,10 @@ SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" import requests - # List of direct_dependencies and their license URLs direct_dependencies = [ # {"name": "tkinter", "license_url": "https://docs.python.org/3/license.html"}, @@ -24,8 +23,10 @@ # {"name": "re", "license_url": "https://docs.python.org/3/license.html"}, # {"name": "webbrowser", "license_url": "https://docs.python.org/3/license.html"}, {"name": "pymavlink", "license_url": "https://raw.githubusercontent.com/ArduPilot/pymavlink/master/COPYING"}, - {"name": "ArduPilot tempcal_IMU.py", - "license_url": "https://raw.githubusercontent.com/ArduPilot/ardupilot/master/COPYING.txt"}, + { + "name": "ArduPilot tempcal_IMU.py", + "license_url": "https://raw.githubusercontent.com/ArduPilot/ardupilot/master/COPYING.txt", + }, {"name": "platformdirs", "license_url": "https://raw.githubusercontent.com/platformdirs/platformdirs/main/LICENSE"}, {"name": "pyserial", "license_url": "https://raw.githubusercontent.com/pyserial/pyserial/master/LICENSE.txt"}, {"name": "Scrollable_TK_frame", "license_url": "https://mozilla.org/MPL/2.0/"}, @@ -36,25 +37,27 @@ # List of direct_dependencies and their license URLs indirect_dependencies = [ {"name": "certifi", "license_url": "https://raw.githubusercontent.com/certifi/python-certifi/master/LICENSE"}, - {"name": "charset-normalizer", - "license_url": "https://raw.githubusercontent.com/Ousret/charset_normalizer/master/LICENSE"}, + { + "name": "charset-normalizer", + "license_url": "https://raw.githubusercontent.com/Ousret/charset_normalizer/master/LICENSE", + }, {"name": "future", "license_url": "https://raw.githubusercontent.com/PythonCharmers/python-future/master/LICENSE.txt"}, {"name": "urllib3", "license_url": "https://raw.githubusercontent.com/urllib3/urllib3/main/LICENSE.txt"}, {"name": "lxml", "license_url": "https://raw.githubusercontent.com/lxml/lxml/master/LICENSE.txt"}, - {"name": "idna", "license_url": "https://raw.githubusercontent.com/kjd/idna/master/LICENSE.md"} + {"name": "idna", "license_url": "https://raw.githubusercontent.com/kjd/idna/master/LICENSE.md"}, ] def download_license(package_name, license_url): try: response = requests.get(license_url, timeout=10) - response.raise_for_status() # Raise an exception if the request failed + response.raise_for_status() # Raise an exception if the request failed # Use a fixed filename for the Mozilla Public License version 2.0 if package_name in ["Scrollable_TK_frame", "Python_Tkinter_ComboBox"]: filename = f"{package_name}-Mozilla_Public_License_version_2.0.html" else: filename = f"{package_name}-{license_url.split('/')[-1]}" - with open(filename, 'wb') as f: + with open(filename, "wb") as f: f.write(response.content) print(f"Downloaded {filename}") except requests.exceptions.RequestException as e: @@ -63,4 +66,4 @@ def download_license(package_name, license_url): # Download each package's license for package in direct_dependencies + indirect_dependencies: - download_license(package['name'].replace(' ', '_'), package['license_url']) + download_license(package["name"].replace(" ", "_"), package["license_url"]) diff --git a/param_reorder.py b/param_reorder.py index 457ec83..7f86d9a 100755 --- a/param_reorder.py +++ b/param_reorder.py @@ -15,13 +15,17 @@ SPDX-License-Identifier: GPL-3.0-or-later """ +import json import os import re -import json SEQUENCE_FILENAME = "configuration_steps_ArduCopter.json" -PYTHON_FILES = ["param_pid_adjustment_update.py", "param_pid_adjustment_update_test.py", - "annotate_params.py", "copy_magfit_pdef_to_template_dirs.py"] +PYTHON_FILES = [ + "param_pid_adjustment_update.py", + "param_pid_adjustment_update_test.py", + "annotate_params.py", + "copy_magfit_pdef_to_template_dirs.py", +] file_renames = {} # Add lines like these to rename files @@ -47,7 +51,7 @@ def reorder_param_files(steps): def loop_relevant_files(renames, steps): - param_dirs = ['.'] + param_dirs = ["."] # Search all *.py, *.json and *.md files in the current directory # and replace all occurrences of the old names with the new names for root, _dirs, files in os.walk("."): @@ -55,11 +59,11 @@ def loop_relevant_files(renames, steps): if file.endswith(".param"): if root not in param_dirs: param_dirs.append(root) - if file == 'LICENSE.md': + if file == "LICENSE.md": continue - if file == 'vehicle_components.json': + if file == "vehicle_components.json": continue - if file == SEQUENCE_FILENAME: + if file == SEQUENCE_FILENAME: uplate_old_filenames(renames, steps) if file in PYTHON_FILES or file.endswith(".md") or file.endswith(".json"): update_file_contents(renames, root, file, steps) @@ -80,12 +84,11 @@ def update_file_contents(renames, root, file, steps): with open(os.path.join(root, file), "r", encoding="utf-8") as handle: file_content = handle.read() if file.startswith("TUNING_GUIDE_") and file.endswith(".md"): - for _new_filename, old_filename in renames.items(): + for old_filename in renames.values(): if old_filename not in file_content: - print(f"Error: The intermediate parameter file '{old_filename}'" \ - f" is not mentioned in the {file} file") + print(f"Error: The intermediate parameter file '{old_filename}'" f" is not mentioned in the {file} file") for new_name, old_name in renames.items(): - if 'configuration_steps' in file and file.endswith(".json"): + if "configuration_steps" in file and file.endswith(".json"): file_content = update_configuration_steps_json_file_contents(steps, file_content, new_name, old_name) else: file_content = file_content.replace(old_name, new_name) @@ -95,15 +98,15 @@ def update_file_contents(renames, root, file, steps): def update_configuration_steps_json_file_contents(steps, file_content, new_name, old_name): new_file_content = "" - curr_filename = '' + curr_filename = "" for line in file_content.splitlines(keepends=True): - re_search = re.search(r'^ \"(\w.+)\"', line) + re_search = re.search(r"^ \"(\w.+)\"", line) if re_search: curr_filename = re_search.group(1) if "old_filenames" in line: if curr_filename in steps and "old_filenames" in steps[curr_filename]: # WARNING!!! old_filenames can only used once, so we remove it after using it - old_filenames = str(steps[curr_filename].pop("old_filenames")).replace("\'", "\"") + old_filenames = str(steps[curr_filename].pop("old_filenames")).replace("'", '"') new_file_content += f' "old_filenames": {old_filenames}' if line.endswith(",\n"): new_file_content += "," @@ -140,13 +143,13 @@ def change_line_endings_for_md_files(): file_path = os.path.join(root, file) with open(file_path, "rb") as handle: content = handle.read() - content = content.replace(b'\n', b'\r\n') + content = content.replace(b"\n", b"\r\n") with open(file_path, "wb") as handle: handle.write(content) def main(): - with open(os.path.join("MethodicConfigurator", SEQUENCE_FILENAME), 'r', encoding='utf-8') as f: + with open(os.path.join("MethodicConfigurator", SEQUENCE_FILENAME), "r", encoding="utf-8") as f: steps = json.load(f) renames = reorder_param_files(steps) param_dirs = loop_relevant_files(renames, steps) diff --git a/setup.py b/setup.py index 80b5d11..3c6afb2 100755 --- a/setup.py +++ b/setup.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 -''' +""" This script creates the MethodicConfigurator pip python package This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator @@ -8,30 +8,29 @@ SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" -import shutil import os +import shutil -from setuptools import setup -from setuptools import find_packages +from setuptools import find_packages, setup from MethodicConfigurator.version import VERSION dev_requirements = [ - 'ruff', - 'pre-commit', - 'pytest', - 'pytest-cov', - 'coverage', - 'mock', + "ruff", + "pre-commit", + "pytest", + "pytest-cov", + "coverage", + "mock", # Add any other development requirements here ] extra_scripts = [ - 'MethodicConfigurator/annotate_params.py', - 'MethodicConfigurator/extract_param_defaults.py', - 'MethodicConfigurator/param_pid_adjustment_update.py' + "MethodicConfigurator/annotate_params.py", + "MethodicConfigurator/extract_param_defaults.py", + "MethodicConfigurator/param_pid_adjustment_update.py", ] PRJ_URL = "https://github.com/ArduPilot/MethodicConfigurator" @@ -42,7 +41,7 @@ os.chmod("MethodicConfigurator/ardupilot_methodic_configurator.py", 0o755) # Read the long description from the README file -with open('README.md', 'r', encoding='utf-8') as f: +with open("README.md", "r", encoding="utf-8") as f: long_description = f.read() # Use Absolute links so that the pyPI page renders correctly long_description = long_description.replace("(USERMANUAL.md", f"({PRJ_URL}/blob/master/USERMANUAL.md") @@ -53,12 +52,13 @@ long_description = long_description.replace("(LICENSE.md", f"({PRJ_URL}/blob/master/LICENSE.md") long_description = long_description.replace("(USECASES.md", f"({PRJ_URL}/blob/master/USECASES.md") long_description = long_description.replace("(credits/CREDITS.md", f"({PRJ_URL}/blob/master/credits/CREDITS.md") - long_description = long_description.replace("images/App_screenshot1.png", - f"{PRJ_URL}/raw/master/images/App_screenshot1.png") + long_description = long_description.replace( + "images/App_screenshot1.png", f"{PRJ_URL}/raw/master/images/App_screenshot1.png" + ) # So that the vehicle_templates directory contents get correctly read by the MANIFEST.in file -TEMPLATES_SRC_DIR = 'vehicle_templates' -TEMPLATES_DST_DIR = 'MethodicConfigurator/vehicle_templates' +TEMPLATES_SRC_DIR = "vehicle_templates" +TEMPLATES_DST_DIR = "MethodicConfigurator/vehicle_templates" if os.path.exists(TEMPLATES_DST_DIR): shutil.rmtree(TEMPLATES_DST_DIR) @@ -71,75 +71,77 @@ except FileExistsError: print(f"The destination directory '{TEMPLATES_DST_DIR}' already exists and cannot be overwritten.") except PermissionError: - print(f"Permission denied when trying to copy '{TEMPLATES_SRC_DIR}' to '{TEMPLATES_DST_DIR}'. " \ - "Please check your permissions.") + print( + f"Permission denied when trying to copy '{TEMPLATES_SRC_DIR}' to '{TEMPLATES_DST_DIR}'. " + "Please check your permissions." + ) except Exception as e: # pylint: disable=broad-except print(f"An unexpected error occurred while copying the directory tree: {e}") setup( - name='MethodicConfigurator', + name="MethodicConfigurator", version=VERSION, zip_safe=True, - description='A clear configuration sequence for ArduPilot vehicles', + description="A clear configuration sequence for ArduPilot vehicles", long_description=long_description, - long_description_content_type='text/markdown', + long_description_content_type="text/markdown", url=PRJ_URL, - author='Amilcar do Carmo Lucas', - author_email='amilcar.lucas@iav.de', + author="Amilcar do Carmo Lucas", + author_email="amilcar.lucas@iav.de", packages=find_packages(), install_requires=[ - 'defusedxml', - 'matplotlib', - 'numpy', - 'platformdirs', - 'pymavlink', - 'pyserial', - 'pillow', - 'setuptools', - 'requests', + "defusedxml", + "matplotlib", + "numpy", + "platformdirs", + "pymavlink", + "pyserial", + "pillow", + "setuptools", + "requests", ], extras_require={ - 'dev': dev_requirements, + "dev": dev_requirements, }, classifiers=[ - 'Development Status :: 4 - Beta', - 'Intended Audience :: Science/Research', - 'License :: OSI Approved :: GNU General Public License v3 (GPLv3)', - 'Operating System :: OS Independent', - 'Programming Language :: Python :: 3', - 'Programming Language :: Python :: 3.6', - 'Programming Language :: Python :: 3.7', - 'Programming Language :: Python :: 3.8', - 'Programming Language :: Python :: 3.9', - 'Programming Language :: Python :: 3.10', - 'Programming Language :: Python :: 3.11', - 'Programming Language :: Python :: 3.12', - 'Topic :: Scientific/Engineering', + "Development Status :: 4 - Beta", + "Intended Audience :: Science/Research", + "License :: OSI Approved :: GNU General Public License v3 (GPLv3)", + "Operating System :: OS Independent", + "Programming Language :: Python :: 3", + "Programming Language :: Python :: 3.6", + "Programming Language :: Python :: 3.7", + "Programming Language :: Python :: 3.8", + "Programming Language :: Python :: 3.9", + "Programming Language :: Python :: 3.10", + "Programming Language :: Python :: 3.11", + "Programming Language :: Python :: 3.12", + "Topic :: Scientific/Engineering", ], # Add the license - license='GPLv3', - python_requires='>=3.6', - keywords=['ArduPilot', 'Configuration', 'SCM', 'Methodic', 'ArduCopter', 'ArduPlane', 'ArduRover', 'ArduSub'], - #package_dir={"": "MethodicConfigurator"}, this unfortunatly breaks the build + license="GPLv3", + python_requires=">=3.6", + keywords=["ArduPilot", "Configuration", "SCM", "Methodic", "ArduCopter", "ArduPlane", "ArduRover", "ArduSub"], + # package_dir={"": "MethodicConfigurator"}, this unfortunatly breaks the build include_package_data=True, scripts=extra_scripts, # Specify entry points for command-line scripts entry_points={ - 'console_scripts': [ - 'ardupilot_methodic_configurator=MethodicConfigurator.ardupilot_methodic_configurator:main', - 'extract_param_defaults=MethodicConfigurator.extract_param_defaults:main', - 'annotate_params=MethodicConfigurator.annotate_params:main', - 'param_pid_adjustment_update=MethodicConfigurator.param_pid_adjustment_update:main', + "console_scripts": [ + "ardupilot_methodic_configurator=MethodicConfigurator.ardupilot_methodic_configurator:main", + "extract_param_defaults=MethodicConfigurator.extract_param_defaults:main", + "annotate_params=MethodicConfigurator.annotate_params:main", + "param_pid_adjustment_update=MethodicConfigurator.param_pid_adjustment_update:main", ], }, project_urls={ - 'Homepage': PRJ_URL, - 'Documentation': f'{PRJ_URL}/blob/master/USERMANUAL.md', - 'Bug Tracker': f'{PRJ_URL}/issues', - 'Source Code': PRJ_URL, - 'Forum': 'https://discuss.ardupilot.org/t/new-ardupilot-methodic-configurator-gui/115038/', - 'Chat': 'https://discord.com/invite/ArduPilot', - 'Download': f'{PRJ_URL}/releases', + "Homepage": PRJ_URL, + "Documentation": f"{PRJ_URL}/blob/master/USERMANUAL.md", + "Bug Tracker": f"{PRJ_URL}/issues", + "Source Code": PRJ_URL, + "Forum": "https://discuss.ardupilot.org/t/new-ardupilot-methodic-configurator-gui/115038/", + "Chat": "https://discord.com/invite/ArduPilot", + "Download": f"{PRJ_URL}/releases", }, ) diff --git a/unittests/annotate_params_test.py b/unittests/annotate_params_test.py index 0b9e9b1..0d1cd84 100755 --- a/unittests/annotate_params_test.py +++ b/unittests/annotate_params_test.py @@ -1,41 +1,42 @@ #!/usr/bin/python3 -''' +""" These are the unit tests for the python script that fetches online ArduPilot parameter documentation (if not cached) and adds it to the specified file or to all *.param and *.parm files in the specified directory. Author: Amilcar do Carmo Lucas -''' +""" # pylint: skip-file -import tempfile -from unittest.mock import patch, mock_open, Mock import os +import tempfile import unittest -import requests -import mock - +from unittest.mock import Mock, mock_open, patch from xml.etree import ElementTree as ET # no parsing, just data-structure manipulation + +import mock +import requests from defusedxml import ElementTree as DET # just parsing, no data-structure manipulation -from MethodicConfigurator.annotate_params import arg_parser -from MethodicConfigurator.annotate_params import main -from MethodicConfigurator.annotate_params import get_xml_data -from MethodicConfigurator.annotate_params import get_xml_url -from MethodicConfigurator.annotate_params import remove_prefix -from MethodicConfigurator.annotate_params import split_into_lines -from MethodicConfigurator.annotate_params import create_doc_dict -from MethodicConfigurator.annotate_params import format_columns -from MethodicConfigurator.annotate_params import update_parameter_documentation -from MethodicConfigurator.annotate_params import print_read_only_params -from MethodicConfigurator.annotate_params import BASE_URL -from MethodicConfigurator.annotate_params import PARAM_DEFINITION_XML_FILE +from MethodicConfigurator.annotate_params import ( + BASE_URL, + PARAM_DEFINITION_XML_FILE, + arg_parser, + create_doc_dict, + format_columns, + get_xml_data, + get_xml_url, + main, + print_read_only_params, + remove_prefix, + split_into_lines, + update_parameter_documentation, +) class TestParamDocsUpdate(unittest.TestCase): # pylint: disable=missing-class-docstring - def setUp(self): # Create a temporary directory self.temp_dir = tempfile.mkdtemp() @@ -49,25 +50,25 @@ def setUp(self): "humanName": "Param 1", "documentation": ["Documentation for Param 1"], "fields": {"Field1": "Value1", "Field2": "Value2"}, - "values": {"Code1": "Value1", "Code2": "Value2"} + "values": {"Code1": "Value1", "Code2": "Value2"}, }, "PARAM2": { "humanName": "Param 2", "documentation": ["Documentation for Param 2"], "fields": {"Field3": "Value3", "Field4": "Value4"}, - "values": {"Code3": "Value3", "Code4": "Value4"} + "values": {"Code3": "Value3", "Code4": "Value4"}, }, "PARAM_1": { "humanName": "Param _ 1", "documentation": ["Documentation for Param_1"], "fields": {"Field_1": "Value_1", "Field_2": "Value_2"}, - "values": {"Code_1": "Value_1", "Code_2": "Value_2"} + "values": {"Code_1": "Value_1", "Code_2": "Value_2"}, }, } - @patch('builtins.open', new_callable=mock_open, read_data='') - @patch('os.path.isfile') - @patch('annotate_params.Par.load_param_file_into_dict') + @patch("builtins.open", new_callable=mock_open, read_data="") + @patch("os.path.isfile") + @patch("annotate_params.Par.load_param_file_into_dict") def test_get_xml_data_local_file(self, mock_load_param, mock_isfile, mock_open): # Mock the isfile function to return True mock_isfile.return_value = True @@ -82,9 +83,9 @@ def test_get_xml_data_local_file(self, mock_load_param, mock_isfile, mock_open): self.assertIsInstance(result, ET.Element) # Assert that the file was opened correctly - mock_open.assert_called_once_with(os.path.join(".", "test.xml"), 'r', encoding='utf-8') + mock_open.assert_called_once_with(os.path.join(".", "test.xml"), "r", encoding="utf-8") - @patch('requests.get') + @patch("requests.get") def test_get_xml_data_remote_file(self, mock_get): # Mock the response mock_get.return_value.status_code = 200 @@ -105,20 +106,21 @@ def test_get_xml_data_remote_file(self, mock_get): # Assert that the requests.get function was called once mock_get.assert_called_once_with("http://example.com/test.xml", timeout=5) - @patch('os.path.isfile') - @patch('annotate_params.Par.load_param_file_into_dict') + @patch("os.path.isfile") + @patch("annotate_params.Par.load_param_file_into_dict") def test_get_xml_data_script_dir_file(self, mock_load_param, mock_isfile): # Mock the isfile function to return False for the current directory and True for the script directory def side_effect(filename): return True + mock_isfile.side_effect = side_effect # Mock the load_param_file_into_dict function to raise FileNotFoundError mock_load_param.side_effect = FileNotFoundError # Mock the open function to return a dummy XML string - mock_open = mock.mock_open(read_data='') - with patch('builtins.open', mock_open): + mock_open = mock.mock_open(read_data="") + with patch("builtins.open", mock_open): # Call the function with a filename that exists in the script directory result = get_xml_data(BASE_URL, ".", PARAM_DEFINITION_XML_FILE, "ArduCopter") @@ -126,12 +128,11 @@ def side_effect(filename): self.assertIsInstance(result, ET.Element) # Assert that the file was opened correctly - mock_open.assert_called_once_with(os.path.join('.', PARAM_DEFINITION_XML_FILE), 'r', encoding='utf-8') + mock_open.assert_called_once_with(os.path.join(".", PARAM_DEFINITION_XML_FILE), "r", encoding="utf-8") def test_get_xml_data_no_requests_package(self): # Temporarily remove the requests module - with patch.dict('sys.modules', {'requests': None}): - + with patch.dict("sys.modules", {"requests": None}): # Remove the test.xml file if it exists try: os.remove("test.xml") @@ -142,7 +143,7 @@ def test_get_xml_data_no_requests_package(self): with self.assertRaises(SystemExit): get_xml_data("http://example.com/", ".", "test.xml", "ArduCopter") - @patch('requests.get') + @patch("requests.get") def test_get_xml_data_request_failure(self, mock_get): # Mock the response mock_get.side_effect = requests.exceptions.RequestException @@ -157,7 +158,7 @@ def test_get_xml_data_request_failure(self, mock_get): with self.assertRaises(SystemExit): get_xml_data("http://example.com/", ".", "test.xml", "ArduCopter") - @patch('requests.get') + @patch("requests.get") def test_get_xml_data_valid_xml(self, mock_get): # Mock the response mock_get.return_value.status_code = 200 @@ -169,7 +170,7 @@ def test_get_xml_data_valid_xml(self, mock_get): # Check the result self.assertIsInstance(result, ET.Element) - @patch('requests.get') + @patch("requests.get") def test_get_xml_data_invalid_xml(self, mock_get): # Mock the response mock_get.return_value.status_code = 200 @@ -185,8 +186,8 @@ def test_get_xml_data_invalid_xml(self, mock_get): with self.assertRaises(ET.ParseError): get_xml_data("http://example.com/", ".", "test.xml", "ArduCopter") - @patch('requests.get') - @patch('os.path.isfile') + @patch("requests.get") + @patch("os.path.isfile") def test_get_xml_data_missing_file(self, mock_isfile, mock_get): # Mock the isfile function to return False mock_isfile.return_value = False @@ -203,7 +204,7 @@ def test_get_xml_data_missing_file(self, mock_isfile, mock_get): with self.assertRaises(FileNotFoundError): get_xml_data("/path/to/local/file/", ".", "test.xml", "ArduCopter") - @patch('requests.get') + @patch("requests.get") def test_get_xml_data_network_issue(self, mock_get): # Mock the response mock_get.side_effect = requests.exceptions.ConnectionError @@ -243,7 +244,7 @@ def test_split_into_lines(self): def test_create_doc_dict(self): # Mock XML data - xml_data = ''' + xml_data = """ Value1 @@ -262,7 +263,7 @@ def test_create_doc_dict(self): - ''' + """ root = DET.fromstring(xml_data) # Expected output @@ -271,14 +272,14 @@ def test_create_doc_dict(self): "humanName": "Param 1", "documentation": ["Documentation for Param 1"], "fields": {"Field1": "Value1", "Field2": "Value2"}, - "values": {"Code1": "Value1", "Code2": "Value2"} + "values": {"Code1": "Value1", "Code2": "Value2"}, }, "PARAM2": { "humanName": "Param 2", "documentation": ["Documentation for Param 2"], "fields": {"Units": "m/s (meters per second)"}, - "values": {"Code3": "Value3", "Code4": "Value4"} - } + "values": {"Code3": "Value3", "Code4": "Value4"}, + }, } # Call the function with the mock XML data @@ -306,12 +307,12 @@ def test_format_columns(self): # Define the expected output expected_output = [ - 'Key1: Value1 Key7: Value7', - 'Key2: Value2 Key8: Value8', - 'Key3: Value3 Key9: Value9', - 'Key4: Value4 Key10: Value10', - 'Key5: Value5 Key11: Value11', - 'Key6: Value6 Key12: Value12', + "Key1: Value1 Key7: Value7", + "Key2: Value2 Key8: Value8", + "Key3: Value3 Key9: Value9", + "Key4: Value4 Key10: Value10", + "Key5: Value5 Key11: Value11", + "Key6: Value6 Key12: Value12", ] # Call the function with the input @@ -355,7 +356,7 @@ def test_update_parameter_documentation_sorting_none(self): with open(self.temp_file.name, "r", encoding="utf-8") as file: updated_content = file.read() - expected_content = '''# Param 2 + expected_content = """# Param 2 # Documentation for Param 2 # Field3: Value3 # Field4: Value4 @@ -381,7 +382,7 @@ def test_update_parameter_documentation_sorting_none(self): # Code1: Value1 # Code2: Value2 PARAM1 100 -''' +""" self.assertEqual(updated_content, expected_content) def test_update_parameter_documentation_sorting_missionplanner(self): @@ -396,7 +397,7 @@ def test_update_parameter_documentation_sorting_missionplanner(self): with open(self.temp_file.name, "r", encoding="utf-8") as file: updated_content = file.read() - expected_content = '''# Param _ 1 + expected_content = """# Param _ 1 # Documentation for Param_1 # Field_1: Value_1 # Field_2: Value_2 @@ -419,7 +420,7 @@ def test_update_parameter_documentation_sorting_missionplanner(self): # Code3: Value3 # Code4: Value4 PARAM2 100 # ignore, me -''' +""" self.assertEqual(updated_content, expected_content) def test_update_parameter_documentation_sorting_mavproxy(self): @@ -434,7 +435,7 @@ def test_update_parameter_documentation_sorting_mavproxy(self): with open(self.temp_file.name, "r", encoding="utf-8") as file: updated_content = file.read() - expected_content = '''# Param 1 + expected_content = """# Param 1 # Documentation for Param 1 # Field1: Value1 # Field2: Value2 @@ -457,7 +458,7 @@ def test_update_parameter_documentation_sorting_mavproxy(self): # Code_1: Value_1 # Code_2: Value_2 PARAM_1\t100 -''' +""" self.assertEqual(updated_content, expected_content) def test_update_parameter_documentation_invalid_line_format(self): @@ -472,10 +473,10 @@ def test_update_parameter_documentation_invalid_line_format(self): # Check if the SystemExit exception contains the expected message self.assertEqual(cm.exception.code, "Invalid line in input file") - @patch('logging.Logger.info') + @patch("logging.Logger.info") def test_print_read_only_params(self, mock_info): # Mock XML data - xml_data = ''' + xml_data = """ True @@ -495,7 +496,7 @@ def test_print_read_only_params(self, mock_info): - ''' + """ root = DET.fromstring(xml_data) doc_dict = create_doc_dict(root, "VehicleType") @@ -503,7 +504,7 @@ def test_print_read_only_params(self, mock_info): print_read_only_params(doc_dict) # Check if the parameter name was logged - mock_info.assert_has_calls([mock.call('ReadOnly parameters:'), mock.call('PARAM1')]) + mock_info.assert_has_calls([mock.call("ReadOnly parameters:"), mock.call("PARAM1")]) def test_update_parameter_documentation_invalid_target(self): # Call the function with an invalid target @@ -528,7 +529,7 @@ def test_update_parameter_documentation_too_long_parameter_name(self): with self.assertRaises(SystemExit): update_parameter_documentation(self.doc_dict, self.temp_file.name) - @patch('logging.Logger.warning') + @patch("logging.Logger.warning") def test_missing_parameter_documentation(self, mock_warning): # Write some initial content to the temporary file with open(self.temp_file.name, "w", encoding="utf-8") as file: @@ -538,10 +539,12 @@ def test_missing_parameter_documentation(self, mock_warning): update_parameter_documentation(self.doc_dict, self.temp_file.name) # Check if the warnings were logged - mock_warning.assert_has_calls([ - mock.call('Read file %s with %d parameters, but only %s of which got documented', self.temp_file.name, 1, 0), - mock.call('No documentation found for: %s', 'MISSING_DOC_PARA') - ]) + mock_warning.assert_has_calls( + [ + mock.call("Read file %s with %d parameters, but only %s of which got documented", self.temp_file.name, 1, 0), + mock.call("No documentation found for: %s", "MISSING_DOC_PARA"), + ] + ) def test_empty_parameter_file(self): # Call the function with the temporary file @@ -556,53 +559,47 @@ def test_empty_parameter_file(self): class AnnotateParamsTest(unittest.TestCase): - def test_arg_parser_valid_arguments(self): - test_args = ['annotate_params', '--vehicle-type', 'ArduCopter', '--sort', 'none', 'parameters'] - with patch('sys.argv', test_args): + test_args = ["annotate_params", "--vehicle-type", "ArduCopter", "--sort", "none", "parameters"] + with patch("sys.argv", test_args): args = arg_parser() - self.assertEqual(args.vehicle_type, 'ArduCopter') - self.assertEqual(args.sort, 'none') - self.assertEqual(args.target, 'parameters') + self.assertEqual(args.vehicle_type, "ArduCopter") + self.assertEqual(args.sort, "none") + self.assertEqual(args.target, "parameters") self.assertEqual(args.verbose, False) self.assertEqual(args.max_line_length, 100) def test_arg_parser_invalid_vehicle_type(self): - test_args = ['annotate_params', '--vehicle-type', 'InvalidType', '--sort', 'none', 'parameters'] - with patch('sys.argv', test_args): + test_args = ["annotate_params", "--vehicle-type", "InvalidType", "--sort", "none", "parameters"] + with patch("sys.argv", test_args): with self.assertRaises(SystemExit): arg_parser() def test_arg_parser_invalid_sort_option(self): - test_args = ['annotate_params', '--vehicle-type', 'ArduCopter', '--sort', 'invalid', 'parameters'] - with patch('sys.argv', test_args): + test_args = ["annotate_params", "--vehicle-type", "ArduCopter", "--sort", "invalid", "parameters"] + with patch("sys.argv", test_args): with self.assertRaises(SystemExit): arg_parser() def test_arg_parser_invalid_line_length_option(self): - test_args = ['annotate_params', '--vehicle-type', 'ArduCopter', '--sort', 'none', '-m', 'invalid', 'parameters'] - with patch('sys.argv', test_args): + test_args = ["annotate_params", "--vehicle-type", "ArduCopter", "--sort", "none", "-m", "invalid", "parameters"] + with patch("sys.argv", test_args): with self.assertRaises(SystemExit): arg_parser() class TestAnnotateParamsExceptionHandling(unittest.TestCase): - - @patch('annotate_params.arg_parser') - @patch('annotate_params.get_xml_url') - @patch('annotate_params.get_xml_dir') - @patch('annotate_params.parse_parameter_metadata') - @patch('annotate_params.update_parameter_documentation') - @patch('builtins.open', new_callable=mock_open) + @patch("annotate_params.arg_parser") + @patch("annotate_params.get_xml_url") + @patch("annotate_params.get_xml_dir") + @patch("annotate_params.parse_parameter_metadata") + @patch("annotate_params.update_parameter_documentation") + @patch("builtins.open", new_callable=mock_open) def test_main_ioerror( self, mock_file, mock_update, mock_parse_metadata, mock_get_xml_dir, mock_get_xml_url, mock_arg_parser ): mock_arg_parser.return_value = Mock( - vehicle_type='ArduCopter', - target='.', - sort='none', - delete_documentation_annotations=False, - verbose=False + vehicle_type="ArduCopter", target=".", sort="none", delete_documentation_annotations=False, verbose=False ) mock_file.side_effect = IOError("Mocked IO Error") @@ -611,21 +608,17 @@ def test_main_ioerror( self.assertIn(cm.exception.code, [1, 2]) - @patch('annotate_params.arg_parser') - @patch('annotate_params.get_xml_url') - @patch('annotate_params.get_xml_dir') - @patch('annotate_params.parse_parameter_metadata') - @patch('annotate_params.update_parameter_documentation') - @patch('builtins.open', new_callable=mock_open) + @patch("annotate_params.arg_parser") + @patch("annotate_params.get_xml_url") + @patch("annotate_params.get_xml_dir") + @patch("annotate_params.parse_parameter_metadata") + @patch("annotate_params.update_parameter_documentation") + @patch("builtins.open", new_callable=mock_open) def test_main_oserror( self, mock_file, mock_update, mock_parse_metadata, mock_get_xml_dir, mock_get_xml_url, mock_arg_parser ): mock_arg_parser.return_value = Mock( - vehicle_type='ArduCopter', - target='.', - sort='none', - delete_documentation_annotations=False, - verbose=False + vehicle_type="ArduCopter", target=".", sort="none", delete_documentation_annotations=False, verbose=False ) mock_file.side_effect = OSError("Mocked OS Error") @@ -634,12 +627,12 @@ def test_main_oserror( self.assertIn(cm.exception.code, [1, 2]) - @patch('annotate_params.get_xml_url') + @patch("annotate_params.get_xml_url") def test_get_xml_url_exception(self, mock_get_xml_url): mock_get_xml_url.side_effect = ValueError("Mocked Value Error") with self.assertRaises(ValueError): - get_xml_url('NonExistingVehicle', '4.0') + get_xml_url("NonExistingVehicle", "4.0") -if __name__ == '__main__': +if __name__ == "__main__": unittest.main() diff --git a/unittests/ardupilot_methodic_configurator_test.py b/unittests/ardupilot_methodic_configurator_test.py index 6c27b02..d7045bd 100755 --- a/unittests/ardupilot_methodic_configurator_test.py +++ b/unittests/ardupilot_methodic_configurator_test.py @@ -1,31 +1,33 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" # pylint: skip-file import argparse import unittest from unittest.mock import patch + # from unittest.mock import MagicMock # from unittest.mock import mock_open from MethodicConfigurator.ardupilot_methodic_configurator import argument_parser class TestArgumentParser(unittest.TestCase): # pylint: disable=missing-class-docstring - @patch('argparse.ArgumentParser.parse_args', - return_value=argparse.Namespace(conn='tcp:127.0.0.1:5760', params='params_dir')) + @patch( + "argparse.ArgumentParser.parse_args", return_value=argparse.Namespace(conn="tcp:127.0.0.1:5760", params="params_dir") + ) def test_argument_parser(self, mock_args): args = argument_parser() - self.assertEqual(args.conn, 'tcp:127.0.0.1:5760') - self.assertEqual(args.params, 'params_dir') + self.assertEqual(args.conn, "tcp:127.0.0.1:5760") + self.assertEqual(args.params, "params_dir") -if __name__ == '__main__': +if __name__ == "__main__": unittest.main() diff --git a/unittests/backend_filesystem_test.py b/unittests/backend_filesystem_test.py index 0a1795f..0d6942b 100755 --- a/unittests/backend_filesystem_test.py +++ b/unittests/backend_filesystem_test.py @@ -1,71 +1,69 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" # pylint: skip-file import unittest -# import os -from unittest.mock import patch -from unittest.mock import MagicMock +# import os +from unittest.mock import MagicMock, patch from MethodicConfigurator.backend_filesystem import LocalFilesystem -class TestLocalFilesystem(): - - @patch('os.path.isdir') - @patch('os.listdir') +class TestLocalFilesystem: + @patch("os.path.isdir") + @patch("os.listdir") def test_read_params_from_files(self, mock_listdir, mock_isdir): # Setup mock_isdir.return_value = True - mock_listdir.return_value = ['00_default.param', '01_ignore_readonly.param', '02_test.param'] + mock_listdir.return_value = ["00_default.param", "01_ignore_readonly.param", "02_test.param"] mock_load_param_file_into_dict = MagicMock() - mock_load_param_file_into_dict.return_value = {'TEST_PARAM': 'value'} + mock_load_param_file_into_dict.return_value = {"TEST_PARAM": "value"} LocalFilesystem.load_param_file_into_dict = mock_load_param_file_into_dict # Call the method under test - lfs = LocalFilesystem('vehicle_dir', 'vehicle_type', None, False) + lfs = LocalFilesystem("vehicle_dir", "vehicle_type", None, False) result = lfs.read_params_from_files() # Assertions - self.assertEqual(result, {'02_test.param': {'TEST_PARAM': 'value'}}) - mock_isdir.assert_called_once_with('vehicle_dir') - mock_listdir.assert_called_once_with('vehicle_dir') - mock_load_param_file_into_dict.assert_called_once_with('vehicle_dir/02_test.param') + self.assertEqual(result, {"02_test.param": {"TEST_PARAM": "value"}}) + mock_isdir.assert_called_once_with("vehicle_dir") + mock_listdir.assert_called_once_with("vehicle_dir") + mock_load_param_file_into_dict.assert_called_once_with("vehicle_dir/02_test.param") def test_str_to_bool(self): - lfs = LocalFilesystem('vehicle_dir', 'vehicle_type', None, False) - self.assertTrue(lfs.str_to_bool('true')) - self.assertTrue(lfs.str_to_bool('yes')) - self.assertTrue(lfs.str_to_bool('1')) - self.assertFalse(lfs.str_to_bool('false')) - self.assertFalse(lfs.str_to_bool('no')) - self.assertFalse(lfs.str_to_bool('0')) - self.assertIsNone(lfs.str_to_bool('maybe')) - - @patch('os.path.isdir') - @patch('os.listdir') - @patch('backend_filesystem.LocalFilesystem.read_params_from_files') + lfs = LocalFilesystem("vehicle_dir", "vehicle_type", None, False) + self.assertTrue(lfs.str_to_bool("true")) + self.assertTrue(lfs.str_to_bool("yes")) + self.assertTrue(lfs.str_to_bool("1")) + self.assertFalse(lfs.str_to_bool("false")) + self.assertFalse(lfs.str_to_bool("no")) + self.assertFalse(lfs.str_to_bool("0")) + self.assertIsNone(lfs.str_to_bool("maybe")) + + @patch("os.path.isdir") + @patch("os.listdir") + @patch("backend_filesystem.LocalFilesystem.read_params_from_files") def test_re_init(self, mock_read_params_from_files, mock_listdir, mock_isdir): mock_isdir.return_value = True - mock_listdir.return_value = ['00_default.param', '01_ignore_readonly.param', '02_test.param'] - mock_read_params_from_files.return_value = {'02_test.param': {'TEST_PARAM': 'value'}} + mock_listdir.return_value = ["00_default.param", "01_ignore_readonly.param", "02_test.param"] + mock_read_params_from_files.return_value = {"02_test.param": {"TEST_PARAM": "value"}} - lfs = LocalFilesystem('vehicle_dir', 'vehicle_type', None, False) - lfs.re_init('new_vehicle_dir', 'new_vehicle_type') + lfs = LocalFilesystem("vehicle_dir", "vehicle_type", None, False) + lfs.re_init("new_vehicle_dir", "new_vehicle_type") - self.assertEqual(lfs.vehicle_dir, 'new_vehicle_dir') - self.assertEqual(lfs.vehicle_type, 'new_vehicle_type') - mock_isdir.assert_called_once_with('new_vehicle_dir') - mock_listdir.assert_called_once_with('new_vehicle_dir') + self.assertEqual(lfs.vehicle_dir, "new_vehicle_dir") + self.assertEqual(lfs.vehicle_type, "new_vehicle_type") + mock_isdir.assert_called_once_with("new_vehicle_dir") + mock_listdir.assert_called_once_with("new_vehicle_dir") mock_read_params_from_files.assert_called_once() def test_write_summary_files(self): @@ -85,33 +83,32 @@ def test_write_summary_files(self): pass -class TestCopyTemplateFilesToNewVehicleDir(): - - @patch('os.listdir') - @patch('os.path.join') - @patch('shutil.copytree') - @patch('shutil.copy2') +class TestCopyTemplateFilesToNewVehicleDir: + @patch("os.listdir") + @patch("os.path.join") + @patch("shutil.copytree") + @patch("shutil.copy2") def test_copy_template_files_to_new_vehicle_dir(self, mock_copy2, mock_copytree, mock_join, mock_listdir): # Ensure the mock for os.listdir returns the expected items - mock_listdir.return_value = ['file1', 'dir1'] + mock_listdir.return_value = ["file1", "dir1"] # Simulate os.path.join behavior to ensure paths are constructed as expected - mock_join.side_effect = lambda *args: '/'.join(args) + mock_join.side_effect = lambda *args: "/".join(args) # Initialize LocalFilesystem - lfs = LocalFilesystem('vehicle_dir', 'vehicle_type', None, False) + lfs = LocalFilesystem("vehicle_dir", "vehicle_type", None, False) # Call the method under test - lfs.copy_template_files_to_new_vehicle_dir('template_dir', 'new_vehicle_dir') + lfs.copy_template_files_to_new_vehicle_dir("template_dir", "new_vehicle_dir") # Assertions to verify the mocks were called as expected - mock_listdir.assert_called_once_with('template_dir') - mock_join.assert_any_call('template_dir', 'file1') - mock_join.assert_any_call('template_dir', 'dir1') - mock_join.assert_any_call('new_vehicle_dir', 'file1') - mock_join.assert_any_call('new_vehicle_dir', 'dir1') - mock_copy2.assert_called_once_with('template_dir/file1', 'new_vehicle_dir/file1') - mock_copytree.assert_called_once_with('template_dir/dir1', 'new_vehicle_dir/dir1') + mock_listdir.assert_called_once_with("template_dir") + mock_join.assert_any_call("template_dir", "file1") + mock_join.assert_any_call("template_dir", "dir1") + mock_join.assert_any_call("new_vehicle_dir", "file1") + mock_join.assert_any_call("new_vehicle_dir", "dir1") + mock_copy2.assert_called_once_with("template_dir/file1", "new_vehicle_dir/file1") + mock_copytree.assert_called_once_with("template_dir/dir1", "new_vehicle_dir/dir1") -if __name__ == '__main__': +if __name__ == "__main__": unittest.main() diff --git a/unittests/backend_mavftp_test.py b/unittests/backend_mavftp_test.py index 9d28083..f5d7193 100755 --- a/unittests/backend_mavftp_test.py +++ b/unittests/backend_mavftp_test.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 -''' +""" MAVLink File Transfer Protocol support test - https://mavlink.io/en/services/ftp.html This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator @@ -8,40 +8,46 @@ SPDX-FileCopyrightText: 2024 Amilcar Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" +import logging import unittest -#from unittest.mock import patch + +# from unittest.mock import patch from io import StringIO -import logging + from pymavlink import mavutil -from MethodicConfigurator.backend_mavftp import FTP_OP, MAVFTP, MAVFTPReturn - -from MethodicConfigurator.backend_mavftp import OP_ListDirectory -from MethodicConfigurator.backend_mavftp import OP_ReadFile -from MethodicConfigurator.backend_mavftp import OP_Ack -from MethodicConfigurator.backend_mavftp import OP_Nack -from MethodicConfigurator.backend_mavftp import ERR_None -from MethodicConfigurator.backend_mavftp import ERR_Fail -from MethodicConfigurator.backend_mavftp import ERR_FailErrno -from MethodicConfigurator.backend_mavftp import ERR_InvalidDataSize -from MethodicConfigurator.backend_mavftp import ERR_InvalidSession -from MethodicConfigurator.backend_mavftp import ERR_NoSessionsAvailable -from MethodicConfigurator.backend_mavftp import ERR_EndOfFile -from MethodicConfigurator.backend_mavftp import ERR_UnknownCommand -from MethodicConfigurator.backend_mavftp import ERR_FileExists -from MethodicConfigurator.backend_mavftp import ERR_FileProtected -from MethodicConfigurator.backend_mavftp import ERR_FileNotFound -#from MethodicConfigurator.backend_mavftp import ERR_NoErrorCodeInPayload -#from MethodicConfigurator.backend_mavftp import ERR_NoErrorCodeInNack -#from MethodicConfigurator.backend_mavftp import ERR_NoFilesystemErrorInPayload -from MethodicConfigurator.backend_mavftp import ERR_InvalidErrorCode -#from MethodicConfigurator.backend_mavftp import ERR_PayloadTooLarge -#from MethodicConfigurator.backend_mavftp import ERR_InvalidOpcode -from MethodicConfigurator.backend_mavftp import ERR_InvalidArguments -from MethodicConfigurator.backend_mavftp import ERR_PutAlreadyInProgress -from MethodicConfigurator.backend_mavftp import ERR_FailToOpenLocalFile -from MethodicConfigurator.backend_mavftp import ERR_RemoteReplyTimeout + +# from MethodicConfigurator.backend_mavftp import ERR_NoErrorCodeInPayload +# from MethodicConfigurator.backend_mavftp import ERR_NoErrorCodeInNack +# from MethodicConfigurator.backend_mavftp import ERR_NoFilesystemErrorInPayload +# from MethodicConfigurator.backend_mavftp import ERR_PayloadTooLarge +# from MethodicConfigurator.backend_mavftp import ERR_InvalidOpcode +from MethodicConfigurator.backend_mavftp import ( + FTP_OP, + MAVFTP, + ERR_EndOfFile, + ERR_Fail, + ERR_FailErrno, + ERR_FailToOpenLocalFile, + ERR_FileExists, + ERR_FileNotFound, + ERR_FileProtected, + ERR_InvalidArguments, + ERR_InvalidDataSize, + ERR_InvalidErrorCode, + ERR_InvalidSession, + ERR_None, + ERR_NoSessionsAvailable, + ERR_PutAlreadyInProgress, + ERR_RemoteReplyTimeout, + ERR_UnknownCommand, + MAVFTPReturn, + OP_Ack, + OP_ListDirectory, + OP_Nack, + OP_ReadFile, +) class TestMAVFTPPayloadDecoding(unittest.TestCase): @@ -50,7 +56,7 @@ class TestMAVFTPPayloadDecoding(unittest.TestCase): def setUp(self): self.log_stream = StringIO() handler = logging.StreamHandler(self.log_stream) - formatter = logging.Formatter('%(levelname)s: %(message)s') + formatter = logging.Formatter("%(levelname)s: %(message)s") handler.setFormatter(formatter) logger = logging.getLogger() logger.addHandler(handler) @@ -78,128 +84,154 @@ def test_logging(self): @staticmethod def ftp_operation(seq: int, opcode: int, req_opcode: int, payload: bytearray) -> FTP_OP: - return FTP_OP(seq=seq, session=1, opcode=opcode, size=0, req_opcode=req_opcode, burst_complete=0, offset=0, - payload=payload) + return FTP_OP( + seq=seq, session=1, opcode=opcode, size=0, req_opcode=req_opcode, burst_complete=0, offset=0, payload=payload + ) def test_decode_ftp_ack_and_nack(self): # Test cases grouped by expected outcome - # pylint: disable=line-too-long test_cases = [ { "name": "Successful Operation", "op": self.ftp_operation(seq=1, opcode=OP_Ack, req_opcode=OP_ListDirectory, payload=None), - "expected_message": "ListDirectory succeeded" + "expected_message": "ListDirectory succeeded", }, { "name": "Generic Failure", "op": self.ftp_operation(seq=2, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_Fail])), - "expected_message": "ListDirectory failed, generic error" + "expected_message": "ListDirectory failed, generic error", }, { "name": "System Error", - "op": self.ftp_operation(seq=3, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_FailErrno, 1])), # System error 1 - "expected_message": "ListDirectory failed, system error 1" + "op": self.ftp_operation( + seq=3, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_FailErrno, 1]) + ), # System error 1 + "expected_message": "ListDirectory failed, system error 1", }, { "name": "Invalid Data Size", - "op": self.ftp_operation(seq=4, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_InvalidDataSize])), - "expected_message": "ListDirectory failed, invalid data size" + "op": self.ftp_operation( + seq=4, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_InvalidDataSize]) + ), + "expected_message": "ListDirectory failed, invalid data size", }, { "name": "Invalid Session", - "op": self.ftp_operation(seq=5, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_InvalidSession])), - "expected_message": "ListDirectory failed, session is not currently open" + "op": self.ftp_operation( + seq=5, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_InvalidSession]) + ), + "expected_message": "ListDirectory failed, session is not currently open", }, { "name": "No Sessions Available", - "op": self.ftp_operation(seq=6, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_NoSessionsAvailable])), - "expected_message": "ListDirectory failed, no sessions available" + "op": self.ftp_operation( + seq=6, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_NoSessionsAvailable]) + ), + "expected_message": "ListDirectory failed, no sessions available", }, { "name": "End of File", "op": self.ftp_operation(seq=7, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_EndOfFile])), - "expected_message": "ListDirectory failed, offset past end of file" + "expected_message": "ListDirectory failed, offset past end of file", }, { "name": "Unknown Command", - "op": self.ftp_operation(seq=8, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_UnknownCommand])), - "expected_message": "ListDirectory failed, unknown command" + "op": self.ftp_operation( + seq=8, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_UnknownCommand]) + ), + "expected_message": "ListDirectory failed, unknown command", }, { "name": "File Exists", "op": self.ftp_operation(seq=9, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_FileExists])), - "expected_message": "ListDirectory failed, file/directory already exists" + "expected_message": "ListDirectory failed, file/directory already exists", }, { "name": "File Protected", - "op": self.ftp_operation(seq=10, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_FileProtected])), - "expected_message": "ListDirectory failed, file/directory is protected" + "op": self.ftp_operation( + seq=10, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_FileProtected]) + ), + "expected_message": "ListDirectory failed, file/directory is protected", }, { "name": "File Not Found", - "op": self.ftp_operation(seq=11, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_FileNotFound])), - "expected_message": "ListDirectory failed, file/directory not found" + "op": self.ftp_operation( + seq=11, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_FileNotFound]) + ), + "expected_message": "ListDirectory failed, file/directory not found", }, { "name": "No Error Code in Payload", "op": self.ftp_operation(seq=12, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=None), - "expected_message": "ListDirectory failed, payload contains no error code" + "expected_message": "ListDirectory failed, payload contains no error code", }, { "name": "No Error Code in Nack", "op": self.ftp_operation(seq=13, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_None])), - "expected_message": "ListDirectory failed, no error code" + "expected_message": "ListDirectory failed, no error code", }, { "name": "No Filesystem Error in Payload", "op": self.ftp_operation(seq=14, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_FailErrno])), - "expected_message": "ListDirectory failed, file-system error missing in payload" + "expected_message": "ListDirectory failed, file-system error missing in payload", }, { "name": "Invalid Error Code", - "op": self.ftp_operation(seq=15, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_InvalidErrorCode])), - "expected_message": "ListDirectory failed, invalid error code" + "op": self.ftp_operation( + seq=15, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_InvalidErrorCode]) + ), + "expected_message": "ListDirectory failed, invalid error code", }, { "name": "Payload Too Large", "op": self.ftp_operation(seq=16, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([0, 0, 0])), - "expected_message": "ListDirectory failed, payload is too long" + "expected_message": "ListDirectory failed, payload is too long", }, { "name": "Invalid Opcode", "op": self.ftp_operation(seq=17, opcode=126, req_opcode=OP_ListDirectory, payload=None), - "expected_message": "ListDirectory failed, invalid opcode 126" + "expected_message": "ListDirectory failed, invalid opcode 126", }, { "name": "Unknown Opcode in Request", - "op": self.ftp_operation(seq=19, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_UnknownCommand])), # Assuming 100 is an unknown opcode - "expected_message": "ListDirectory failed, unknown command" + "op": self.ftp_operation( + seq=19, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_UnknownCommand]) + ), # Assuming 100 is an unknown opcode + "expected_message": "ListDirectory failed, unknown command", }, { "name": "Payload with System Error", - "op": self.ftp_operation(seq=20, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_FailErrno, 2])), # System error 2 - "expected_message": "ListDirectory failed, system error 2" + "op": self.ftp_operation( + seq=20, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([ERR_FailErrno, 2]) + ), # System error 2 + "expected_message": "ListDirectory failed, system error 2", }, { "name": "Invalid Error Code in Payload", - "op": self.ftp_operation(seq=21, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([105])), # Assuming 105 is an invalid error code - "expected_message": "ListDirectory failed, invalid error code 105" + "op": self.ftp_operation( + seq=21, opcode=OP_Nack, req_opcode=OP_ListDirectory, payload=bytes([105]) + ), # Assuming 105 is an invalid error code + "expected_message": "ListDirectory failed, invalid error code 105", }, { "name": "Invalid Opcode with Payload", - "op": self.ftp_operation(seq=23, opcode=126, req_opcode=OP_ReadFile, payload=bytes([1, 1])), # Invalid opcode with payload - "expected_message": "ReadFile failed, invalid opcode 126" + "op": self.ftp_operation( + seq=23, opcode=126, req_opcode=OP_ReadFile, payload=bytes([1, 1]) + ), # Invalid opcode with payload + "expected_message": "ReadFile failed, invalid opcode 126", }, # Add more test cases as needed... ] - # pylint: enable=line-too-long for case in test_cases: - ret = self.mav_ftp._MAVFTP__decode_ftp_ack_and_nack(case['op']) # pylint: disable=protected-access + ret = self.mav_ftp._MAVFTP__decode_ftp_ack_and_nack(case["op"]) # pylint: disable=protected-access ret.display_message() log_output = self.log_stream.getvalue().strip() - self.assertIn(case["expected_message"], log_output, - f"Test {case['name']}: Expected {case['expected_message']} but got {log_output}") + self.assertIn( + case["expected_message"], + log_output, + f"Test {case['name']}: Expected {case['expected_message']} but got {log_output}", + ) self.log_stream.seek(0) self.log_stream.truncate(0) @@ -217,8 +249,11 @@ def test_decode_ftp_ack_and_nack(self): ret.error_code = 125 # Set error code to 125 to trigger unknown error message ret.display_message() log_output = self.log_stream.getvalue().strip() - self.assertIn("ListDirectory failed, unknown error 125 in display_message()", log_output, - "Expected unknown error message for unknown error code") + self.assertIn( + "ListDirectory failed, unknown error 125 in display_message()", + log_output, + "Expected unknown error message for unknown error code", + ) self.log_stream.seek(0) self.log_stream.truncate(0) @@ -247,5 +282,5 @@ def test_decode_ftp_ack_and_nack(self): self.log_stream.truncate(0) -if __name__ == '__main__': +if __name__ == "__main__": unittest.main() diff --git a/unittests/battery_cell_voltages_test.py b/unittests/battery_cell_voltages_test.py index 6967b40..de00429 100644 --- a/unittests/battery_cell_voltages_test.py +++ b/unittests/battery_cell_voltages_test.py @@ -1,65 +1,69 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" import unittest from math import nan -from MethodicConfigurator.battery_cell_voltages import battery_cell_voltages -from MethodicConfigurator.battery_cell_voltages import BatteryCell +from MethodicConfigurator.battery_cell_voltages import BatteryCell, battery_cell_voltages class TestBatteryCell(unittest.TestCase): # pylint: disable=missing-class-docstring - def test_chemistries(self): - expected_chemistries = ['LiIon', 'LiIonSS', 'LiIonSSHV', 'Lipo', 'LipoHV', 'LipoHVSS'] + expected_chemistries = ["LiIon", "LiIonSS", "LiIonSSHV", "Lipo", "LipoHV", "LipoHVSS"] chemistries = BatteryCell.chemistries() self.assertEqual(chemistries, expected_chemistries) def test_limit_max_voltage(self): - self.assertEqual(BatteryCell.limit_max_voltage('LiIon'), 4.1) - self.assertEqual(BatteryCell.limit_max_voltage('LipoHV'), 4.35) - self.assertEqual(BatteryCell.limit_max_voltage('NonExistentChemistry'), 4.45) + self.assertEqual(BatteryCell.limit_max_voltage("LiIon"), 4.1) + self.assertEqual(BatteryCell.limit_max_voltage("LipoHV"), 4.35) + self.assertEqual(BatteryCell.limit_max_voltage("NonExistentChemistry"), 4.45) def test_limit_min_voltage(self): - self.assertEqual(BatteryCell.limit_min_voltage('LiIon'), 2.5) - self.assertEqual(BatteryCell.limit_min_voltage('LipoHV'), 3.0) - self.assertEqual(BatteryCell.limit_min_voltage('NonExistentChemistry'), 2.4) + self.assertEqual(BatteryCell.limit_min_voltage("LiIon"), 2.5) + self.assertEqual(BatteryCell.limit_min_voltage("LipoHV"), 3.0) + self.assertEqual(BatteryCell.limit_min_voltage("NonExistentChemistry"), 2.4) def test_recommended_max_voltage(self): - self.assertEqual(BatteryCell.recommended_max_voltage('LiIon'), 4.1) - self.assertIs(BatteryCell.recommended_max_voltage('NonExistentChemistry'), nan) + self.assertEqual(BatteryCell.recommended_max_voltage("LiIon"), 4.1) + self.assertIs(BatteryCell.recommended_max_voltage("NonExistentChemistry"), nan) def test_recommended_low_voltage(self): - self.assertEqual(BatteryCell.recommended_low_voltage('LiIon'), 3.1) - self.assertIs(BatteryCell.recommended_low_voltage('NonExistentChemistry'), nan) + self.assertEqual(BatteryCell.recommended_low_voltage("LiIon"), 3.1) + self.assertIs(BatteryCell.recommended_low_voltage("NonExistentChemistry"), nan) def test_recommended_crit_voltage(self): - self.assertEqual(BatteryCell.recommended_crit_voltage('LiIon'), 2.8) - self.assertIs(BatteryCell.recommended_crit_voltage('NonExistentChemistry'), nan) + self.assertEqual(BatteryCell.recommended_crit_voltage("LiIon"), 2.8) + self.assertIs(BatteryCell.recommended_crit_voltage("NonExistentChemistry"), nan) def test_voltage_monoticity(self): for chemistry in BatteryCell.chemistries(): with self.subTest(chemistry=chemistry): - self.assertEqual(BatteryCell.limit_max_voltage(chemistry), - battery_cell_voltages[chemistry].get('absolute_max')) - self.assertEqual(BatteryCell.limit_min_voltage(chemistry), - battery_cell_voltages[chemistry].get('absolute_min')) - self.assertGreaterEqual(BatteryCell.limit_max_voltage(chemistry), - BatteryCell.recommended_max_voltage(chemistry)) - self.assertGreaterEqual(BatteryCell.recommended_max_voltage(chemistry), - BatteryCell.recommended_low_voltage(chemistry)) - self.assertGreaterEqual(BatteryCell.recommended_low_voltage(chemistry), - BatteryCell.recommended_crit_voltage(chemistry)) - self.assertGreaterEqual(BatteryCell.recommended_crit_voltage(chemistry), - BatteryCell.limit_min_voltage(chemistry)) - - -if __name__ == '__main__': + self.assertEqual( + BatteryCell.limit_max_voltage(chemistry), battery_cell_voltages[chemistry].get("absolute_max") + ) + self.assertEqual( + BatteryCell.limit_min_voltage(chemistry), battery_cell_voltages[chemistry].get("absolute_min") + ) + self.assertGreaterEqual( + BatteryCell.limit_max_voltage(chemistry), BatteryCell.recommended_max_voltage(chemistry) + ) + self.assertGreaterEqual( + BatteryCell.recommended_max_voltage(chemistry), BatteryCell.recommended_low_voltage(chemistry) + ) + self.assertGreaterEqual( + BatteryCell.recommended_low_voltage(chemistry), BatteryCell.recommended_crit_voltage(chemistry) + ) + self.assertGreaterEqual( + BatteryCell.recommended_crit_voltage(chemistry), BatteryCell.limit_min_voltage(chemistry) + ) + + +if __name__ == "__main__": unittest.main() diff --git a/unittests/common_arguments_test.py b/unittests/common_arguments_test.py index 8fd37b6..3421f12 100644 --- a/unittests/common_arguments_test.py +++ b/unittests/common_arguments_test.py @@ -1,33 +1,32 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" import unittest -from unittest.mock import MagicMock from argparse import ArgumentParser +from unittest.mock import MagicMock from MethodicConfigurator import common_arguments class TestCommonArguments(unittest.TestCase): # pylint: disable=missing-class-docstring - def test_add_common_arguments_and_parse_loglevel(self): # Test that loglevel choices are added correctly parser = ArgumentParser() - parser.parse_args = MagicMock(return_value=MagicMock(loglevel='INFO')) + parser.parse_args = MagicMock(return_value=MagicMock(loglevel="INFO")) updated_parser = common_arguments.add_common_arguments_and_parse(parser) # This will raise an error if loglevel is not an argument # or if the choices are not set up correctly. - updated_parser.parse_args(['--loglevel', 'INFO']) - updated_parser.parse_args.assert_called_with(['--loglevel', 'INFO']) + updated_parser.parse_args(["--loglevel", "INFO"]) + updated_parser.parse_args.assert_called_with(["--loglevel", "INFO"]) def test_version_argument(self): # Test that version argument displays correct version @@ -39,9 +38,9 @@ def test_version_argument(self): # We assume the call to parse_args with --version should print the version # Since we cannot capture stdout here easily, we'll just confirm the method was called with --version - updated_parser.parse_args(['--version']) - updated_parser.parse_args.assert_called_with(['--version']) + updated_parser.parse_args(["--version"]) + updated_parser.parse_args.assert_called_with(["--version"]) -if __name__ == '__main__': +if __name__ == "__main__": unittest.main() diff --git a/unittests/extract_param_defaults_test.py b/unittests/extract_param_defaults_test.py index edbc86f..83baa33 100755 --- a/unittests/extract_param_defaults_test.py +++ b/unittests/extract_param_defaults_test.py @@ -1,108 +1,107 @@ #!/usr/bin/python3 -''' +""" Extracts parameter default values from an ArduPilot .bin log file. Unittests. SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' - +""" import unittest -from unittest.mock import patch -from unittest.mock import MagicMock +from unittest.mock import MagicMock, patch -from MethodicConfigurator.extract_param_defaults import extract_parameter_values -from MethodicConfigurator.extract_param_defaults import missionplanner_sort -from MethodicConfigurator.extract_param_defaults import mavproxy_sort -from MethodicConfigurator.extract_param_defaults import sort_params -from MethodicConfigurator.extract_param_defaults import output_params -from MethodicConfigurator.extract_param_defaults import parse_arguments -from MethodicConfigurator.extract_param_defaults import NO_DEFAULT_VALUES_MESSAGE -from MethodicConfigurator.extract_param_defaults import MAVLINK_SYSID_MAX -from MethodicConfigurator.extract_param_defaults import MAVLINK_COMPID_MAX +from MethodicConfigurator.extract_param_defaults import ( + MAVLINK_COMPID_MAX, + MAVLINK_SYSID_MAX, + NO_DEFAULT_VALUES_MESSAGE, + extract_parameter_values, + mavproxy_sort, + missionplanner_sort, + output_params, + parse_arguments, + sort_params, +) class TestArgParseParameters(unittest.TestCase): # pylint: disable=missing-class-docstring def test_command_line_arguments_combinations(self): # Check the 'format' and 'sort' default parameters - args = parse_arguments(['dummy.bin']) - self.assertEqual(args.format, 'missionplanner') - self.assertEqual(args.sort, 'missionplanner') + args = parse_arguments(["dummy.bin"]) + self.assertEqual(args.format, "missionplanner") + self.assertEqual(args.sort, "missionplanner") # Check the 'format' and 'sort' parameters to see if 'sort' can be explicitly overwritten - args = parse_arguments(['-s', 'none', 'dummy.bin']) - self.assertEqual(args.format, 'missionplanner') - self.assertEqual(args.sort, 'none') + args = parse_arguments(["-s", "none", "dummy.bin"]) + self.assertEqual(args.format, "missionplanner") + self.assertEqual(args.sort, "none") # Check the 'format' and 'sort' parameters to see if 'sort' can be implicitly overwritten (mavproxy) - args = parse_arguments(['-f', 'mavproxy', 'dummy.bin']) - self.assertEqual(args.format, 'mavproxy') - self.assertEqual(args.sort, 'mavproxy') + args = parse_arguments(["-f", "mavproxy", "dummy.bin"]) + self.assertEqual(args.format, "mavproxy") + self.assertEqual(args.sort, "mavproxy") # Check the 'format' and 'sort' parameters to see if 'sort' can be implicitly overwritten (qgcs) - args = parse_arguments(['-f', 'qgcs', 'dummy.bin']) - self.assertEqual(args.format, 'qgcs') - self.assertEqual(args.sort, 'qgcs') + args = parse_arguments(["-f", "qgcs", "dummy.bin"]) + self.assertEqual(args.format, "qgcs") + self.assertEqual(args.sort, "qgcs") # Check the 'format' and 'sort' parameters - args = parse_arguments(['-f', 'mavproxy', '-s', 'none', 'dummy.bin']) - self.assertEqual(args.format, 'mavproxy') - self.assertEqual(args.sort, 'none') + args = parse_arguments(["-f", "mavproxy", "-s", "none", "dummy.bin"]) + self.assertEqual(args.format, "mavproxy") + self.assertEqual(args.sort, "none") # Assert that a SystemExit is raised when --sysid is used without --format set to qgcs with self.assertRaises(SystemExit): - with patch('builtins.print') as mock_print: - parse_arguments(['-f', 'mavproxy', '-i', '7', 'dummy.bin']) + with patch("builtins.print") as mock_print: + parse_arguments(["-f", "mavproxy", "-i", "7", "dummy.bin"]) mock_print.assert_called_once_with("--sysid parameter is only relevant if --format is qgcs") # Assert that a SystemExit is raised when --compid is used without --format set to qgcs with self.assertRaises(SystemExit): - with patch('builtins.print') as mock_print: - parse_arguments(['-f', 'missionplanner', '-c', '3', 'dummy.bin']) + with patch("builtins.print") as mock_print: + parse_arguments(["-f", "missionplanner", "-c", "3", "dummy.bin"]) mock_print.assert_called_once_with("--compid parameter is only relevant if --format is qgcs") # Assert that a valid sysid and compid are parsed correctly - args = parse_arguments(['-f', 'qgcs', '-i', '7', '-c', '3', 'dummy.bin']) - self.assertEqual(args.format, 'qgcs') - self.assertEqual(args.sort, 'qgcs') + args = parse_arguments(["-f", "qgcs", "-i", "7", "-c", "3", "dummy.bin"]) + self.assertEqual(args.format, "qgcs") + self.assertEqual(args.sort, "qgcs") self.assertEqual(args.sysid, 7) self.assertEqual(args.compid, 3) class TestExtractParameterDefaultValues(unittest.TestCase): # pylint: disable=missing-class-docstring - - @patch('extract_param_defaults.mavutil.mavlink_connection') + @patch("extract_param_defaults.mavutil.mavlink_connection") def test_logfile_does_not_exist(self, mock_mavlink_connection): # Mock the mavlink connection to raise an exception mock_mavlink_connection.side_effect = Exception("Test exception") # Call the function with a dummy logfile path with self.assertRaises(SystemExit) as cm: - extract_parameter_values('dummy.bin') + extract_parameter_values("dummy.bin") # Check the error message self.assertEqual(str(cm.exception), "Error opening the dummy.bin logfile: Test exception") - @patch('extract_param_defaults.mavutil.mavlink_connection') + @patch("extract_param_defaults.mavutil.mavlink_connection") def test_extract_parameter_default_values(self, mock_mavlink_connection): # Mock the mavlink connection and the messages it returns mock_mlog = MagicMock() mock_mavlink_connection.return_value = mock_mlog mock_mlog.recv_match.side_effect = [ - MagicMock(Name='PARAM1', Default=1.1), - MagicMock(Name='PARAM2', Default=2.0), - None # End of messages + MagicMock(Name="PARAM1", Default=1.1), + MagicMock(Name="PARAM2", Default=2.0), + None, # End of messages ] # Call the function with a dummy logfile path - defaults = extract_parameter_values('dummy.bin') + defaults = extract_parameter_values("dummy.bin") # Check if the defaults dictionary contains the correct parameters and values - self.assertEqual(defaults, {'PARAM1': 1.1, 'PARAM2': 2.0}) + self.assertEqual(defaults, {"PARAM1": 1.1, "PARAM2": 2.0}) - @patch('extract_param_defaults.mavutil.mavlink_connection') + @patch("extract_param_defaults.mavutil.mavlink_connection") def test_no_parameters(self, mock_mavlink_connection): # Mock the mavlink connection to return no parameter messages mock_mlog = MagicMock() @@ -111,10 +110,10 @@ def test_no_parameters(self, mock_mavlink_connection): # Call the function with a dummy logfile path and assert SystemExit is raised with the correct message with self.assertRaises(SystemExit) as cm: - extract_parameter_values('dummy.bin') + extract_parameter_values("dummy.bin") self.assertEqual(str(cm.exception), NO_DEFAULT_VALUES_MESSAGE) - @patch('extract_param_defaults.mavutil.mavlink_connection') + @patch("extract_param_defaults.mavutil.mavlink_connection") def test_no_parameter_defaults(self, mock_mavlink_connection): # Mock the mavlink connection to simulate no parameter default values in the .bin file mock_mlog = MagicMock() @@ -123,200 +122,206 @@ def test_no_parameter_defaults(self, mock_mavlink_connection): # Call the function with a dummy logfile path and assert SystemExit is raised with the correct message with self.assertRaises(SystemExit) as cm: - extract_parameter_values('dummy.bin') + extract_parameter_values("dummy.bin") self.assertEqual(str(cm.exception), NO_DEFAULT_VALUES_MESSAGE) - @patch('extract_param_defaults.mavutil.mavlink_connection') + @patch("extract_param_defaults.mavutil.mavlink_connection") def test_invalid_parameter_name(self, mock_mavlink_connection): # Mock the mavlink connection to simulate an invalid parameter name mock_mlog = MagicMock() mock_mavlink_connection.return_value = mock_mlog - mock_mlog.recv_match.return_value = MagicMock(Name='INVALID_NAME%', Default=1.0) + mock_mlog.recv_match.return_value = MagicMock(Name="INVALID_NAME%", Default=1.0) # Call the function with a dummy logfile path with self.assertRaises(SystemExit): - extract_parameter_values('dummy.bin') + extract_parameter_values("dummy.bin") - @patch('extract_param_defaults.mavutil.mavlink_connection') + @patch("extract_param_defaults.mavutil.mavlink_connection") def test_long_parameter_name(self, mock_mavlink_connection): # Mock the mavlink connection to simulate a too long parameter name mock_mlog = MagicMock() mock_mavlink_connection.return_value = mock_mlog - mock_mlog.recv_match.return_value = MagicMock(Name='TOO_LONG_PARAMETER_NAME', Default=1.0) + mock_mlog.recv_match.return_value = MagicMock(Name="TOO_LONG_PARAMETER_NAME", Default=1.0) # Call the function with a dummy logfile path with self.assertRaises(SystemExit): - extract_parameter_values('dummy.bin') + extract_parameter_values("dummy.bin") class TestSortFunctions(unittest.TestCase): # pylint: disable=missing-class-docstring def test_missionplanner_sort(self): # Define a list of parameter names - params = ['PARAM_GROUP1_PARAM1', 'PARAM_GROUP2_PARAM2', 'PARAM_GROUP1_PARAM2'] + params = ["PARAM_GROUP1_PARAM1", "PARAM_GROUP2_PARAM2", "PARAM_GROUP1_PARAM2"] # Sort the parameters using the missionplanner_sort function sorted_params = sorted(params, key=missionplanner_sort) # Check if the parameters were sorted correctly - self.assertEqual(sorted_params, ['PARAM_GROUP1_PARAM1', 'PARAM_GROUP1_PARAM2', 'PARAM_GROUP2_PARAM2']) + self.assertEqual(sorted_params, ["PARAM_GROUP1_PARAM1", "PARAM_GROUP1_PARAM2", "PARAM_GROUP2_PARAM2"]) # Test with a parameter name that doesn't contain an underscore - params = ['PARAM1', 'PARAM3', 'PARAM2'] + params = ["PARAM1", "PARAM3", "PARAM2"] sorted_params = sorted(params, key=missionplanner_sort) - self.assertEqual(sorted_params, ['PARAM1', 'PARAM2', 'PARAM3']) + self.assertEqual(sorted_params, ["PARAM1", "PARAM2", "PARAM3"]) def test_mavproxy_sort(self): # Define a list of parameter names - params = ['PARAM_GROUP1_PARAM1', 'PARAM_GROUP2_PARAM2', 'PARAM_GROUP1_PARAM2'] + params = ["PARAM_GROUP1_PARAM1", "PARAM_GROUP2_PARAM2", "PARAM_GROUP1_PARAM2"] # Sort the parameters using the mavproxy_sort function sorted_params = sorted(params, key=mavproxy_sort) # Check if the parameters were sorted correctly - self.assertEqual(sorted_params, ['PARAM_GROUP1_PARAM1', 'PARAM_GROUP1_PARAM2', 'PARAM_GROUP2_PARAM2']) + self.assertEqual(sorted_params, ["PARAM_GROUP1_PARAM1", "PARAM_GROUP1_PARAM2", "PARAM_GROUP2_PARAM2"]) # Test with a parameter name that doesn't contain an underscore - params = ['PARAM1', 'PARAM3', 'PARAM2'] + params = ["PARAM1", "PARAM3", "PARAM2"] sorted_params = sorted(params, key=mavproxy_sort) - self.assertEqual(sorted_params, ['PARAM1', 'PARAM2', 'PARAM3']) + self.assertEqual(sorted_params, ["PARAM1", "PARAM2", "PARAM3"]) class TestOutputParams(unittest.TestCase): # pylint: disable=missing-class-docstring - - @patch('builtins.print') + @patch("builtins.print") def test_output_params(self, mock_print): # Prepare a dummy defaults dictionary - defaults = {'PARAM2': 1.0, 'PARAM1': 2.0} + defaults = {"PARAM2": 1.0, "PARAM1": 2.0} # Call the function with the dummy dictionary, 'missionplanner' format type - output_params(defaults, 'missionplanner') + output_params(defaults, "missionplanner") # Check if the print function was called with the correct parameters - expected_calls = [unittest.mock.call('PARAM2,1'), unittest.mock.call('PARAM1,2')] + expected_calls = [unittest.mock.call("PARAM2,1"), unittest.mock.call("PARAM1,2")] print(mock_print.mock_calls) print(expected_calls) mock_print.assert_has_calls(expected_calls, any_order=False) - @patch('builtins.print') + @patch("builtins.print") def test_output_params_missionplanner_non_numeric(self, mock_print): # Prepare a dummy defaults dictionary - defaults = {'PARAM1': 'non-numeric'} + defaults = {"PARAM1": "non-numeric"} # Call the function with the dummy dictionary, 'missionplanner' format type - output_params(defaults, 'missionplanner') + output_params(defaults, "missionplanner") # Check if the print function was called with the correct parameters - expected_calls = [unittest.mock.call('PARAM1,non-numeric')] + expected_calls = [unittest.mock.call("PARAM1,non-numeric")] mock_print.assert_has_calls(expected_calls, any_order=False) - @patch('builtins.print') + @patch("builtins.print") def test_output_params_mavproxy(self, mock_print): # Prepare a dummy defaults dictionary - defaults = {'PARAM2': 2.0, 'PARAM1': 1.0} + defaults = {"PARAM2": 2.0, "PARAM1": 1.0} # Call the function with the dummy dictionary, 'mavproxy' format type and 'mavproxy' sort type - defaults = sort_params(defaults, 'mavproxy') - output_params(defaults, 'mavproxy') + defaults = sort_params(defaults, "mavproxy") + output_params(defaults, "mavproxy") # Check if the print function was called with the correct parameters - expected_calls = [unittest.mock.call("%-15s %.6f" % ('PARAM1', 1.0)), # pylint: disable=consider-using-f-string - unittest.mock.call("%-15s %.6f" % ('PARAM2', 2.0))] # pylint: disable=consider-using-f-string + expected_calls = [ + unittest.mock.call("%-15s %.6f" % ("PARAM1", 1.0)), # pylint: disable=consider-using-f-string + unittest.mock.call("%-15s %.6f" % ("PARAM2", 2.0)), # pylint: disable=consider-using-f-string + ] mock_print.assert_has_calls(expected_calls, any_order=False) - @patch('builtins.print') + @patch("builtins.print") def test_output_params_qgcs(self, mock_print): # Prepare a dummy defaults dictionary - defaults = {'PARAM2': 2.0, 'PARAM1': 1.0} + defaults = {"PARAM2": 2.0, "PARAM1": 1.0} # Call the function with the dummy dictionary, 'qgcs' format type and 'qgcs' sort type - defaults = sort_params(defaults, 'qgcs') - output_params(defaults, 'qgcs') + defaults = sort_params(defaults, "qgcs") + output_params(defaults, "qgcs") # Check if the print function was called with the correct parameters - expected_calls = [unittest.mock.call("\n# # Vehicle-Id Component-Id Name Value Type\n"), - unittest.mock.call("%u %u %-15s %.6f %u" % (1, 1, 'PARAM1', 1.0, 9)), # pylint: disable=consider-using-f-string - unittest.mock.call("%u %u %-15s %.6f %u" % (1, 1, 'PARAM2', 2.0, 9))] # pylint: disable=consider-using-f-string + expected_calls = [ + unittest.mock.call("\n# # Vehicle-Id Component-Id Name Value Type\n"), + unittest.mock.call("%u %u %-15s %.6f %u" % (1, 1, "PARAM1", 1.0, 9)), # pylint: disable=consider-using-f-string + unittest.mock.call("%u %u %-15s %.6f %u" % (1, 1, "PARAM2", 2.0, 9)), # pylint: disable=consider-using-f-string + ] mock_print.assert_has_calls(expected_calls, any_order=False) - @patch('builtins.print') + @patch("builtins.print") def test_output_params_qgcs_2_4(self, mock_print): # Prepare a dummy defaults dictionary - defaults = {'PARAM2': 2.0, 'PARAM1': 1.0} + defaults = {"PARAM2": 2.0, "PARAM1": 1.0} # Call the function with the dummy dictionary, 'qgcs' format type and 'qgcs' sort type - defaults = sort_params(defaults, 'qgcs') - output_params(defaults, 'qgcs', 2, 4) + defaults = sort_params(defaults, "qgcs") + output_params(defaults, "qgcs", 2, 4) # Check if the print function was called with the correct parameters - expected_calls = [unittest.mock.call("\n# # Vehicle-Id Component-Id Name Value Type\n"), - unittest.mock.call("%u %u %-15s %.6f %u" % (2, 4, 'PARAM1', 1.0, 9)), # pylint: disable=consider-using-f-string - unittest.mock.call("%u %u %-15s %.6f %u" % (2, 4, 'PARAM2', 2.0, 9))] # pylint: disable=consider-using-f-string + expected_calls = [ + unittest.mock.call("\n# # Vehicle-Id Component-Id Name Value Type\n"), + unittest.mock.call("%u %u %-15s %.6f %u" % (2, 4, "PARAM1", 1.0, 9)), # pylint: disable=consider-using-f-string + unittest.mock.call("%u %u %-15s %.6f %u" % (2, 4, "PARAM2", 2.0, 9)), # pylint: disable=consider-using-f-string + ] mock_print.assert_has_calls(expected_calls, any_order=False) - @patch('builtins.print') + @patch("builtins.print") def test_output_params_qgcs_SYSID_THISMAV(self, mock_print): # pylint: disable=invalid-name # Prepare a dummy defaults dictionary - defaults = {'PARAM2': 2.0, 'PARAM1': 1.0, 'SYSID_THISMAV': 3.0} + defaults = {"PARAM2": 2.0, "PARAM1": 1.0, "SYSID_THISMAV": 3.0} # Call the function with the dummy dictionary, 'qgcs' format type and 'qgcs' sort type - defaults = sort_params(defaults, 'qgcs') - output_params(defaults, 'qgcs', -1, 7) + defaults = sort_params(defaults, "qgcs") + output_params(defaults, "qgcs", -1, 7) # Check if the print function was called with the correct parameters - expected_calls = [unittest.mock.call("\n# # Vehicle-Id Component-Id Name Value Type\n"), - unittest.mock.call("%u %u %-15s %.6f %u" % (3, 7, 'PARAM1', 1.0, 9)), # pylint: disable=consider-using-f-string - unittest.mock.call("%u %u %-15s %.6f %u" % (3, 7, 'PARAM2', 2.0, 9)), # pylint: disable=consider-using-f-string - unittest.mock.call("%u %u %-15s %.6f %u" % (3, 7, 'SYSID_THISMAV', 3.0, 9))] # pylint: disable=consider-using-f-string + expected_calls = [ + unittest.mock.call("\n# # Vehicle-Id Component-Id Name Value Type\n"), + unittest.mock.call("%u %u %-15s %.6f %u" % (3, 7, "PARAM1", 1.0, 9)), # pylint: disable=consider-using-f-string + unittest.mock.call("%u %u %-15s %.6f %u" % (3, 7, "PARAM2", 2.0, 9)), # pylint: disable=consider-using-f-string + unittest.mock.call("%u %u %-15s %.6f %u" % (3, 7, "SYSID_THISMAV", 3.0, 9)), # pylint: disable=consider-using-f-string + ] mock_print.assert_has_calls(expected_calls, any_order=False) - @patch('builtins.print') + @patch("builtins.print") def test_output_params_qgcs_SYSID_INVALID(self, _mock_print): # pylint: disable=invalid-name # Prepare a dummy defaults dictionary - defaults = {'PARAM2': 2.0, 'PARAM1': 1.0, 'SYSID_THISMAV': -1.0} + defaults = {"PARAM2": 2.0, "PARAM1": 1.0, "SYSID_THISMAV": -1.0} # Assert that a SystemExit is raised with the correct message when an invalid sysid is used with self.assertRaises(SystemExit) as cm: - defaults = sort_params(defaults, 'qgcs') - output_params(defaults, 'qgcs', -1, 7) + defaults = sort_params(defaults, "qgcs") + output_params(defaults, "qgcs", -1, 7) self.assertEqual(str(cm.exception), "Invalid system ID parameter -1 must not be negative") # Assert that a SystemExit is raised with the correct message when an invalid sysid is used with self.assertRaises(SystemExit) as cm: - defaults = sort_params(defaults, 'qgcs') - output_params(defaults, 'qgcs', MAVLINK_SYSID_MAX+2, 7) + defaults = sort_params(defaults, "qgcs") + output_params(defaults, "qgcs", MAVLINK_SYSID_MAX + 2, 7) self.assertEqual(str(cm.exception), f"Invalid system ID parameter 16777218 must be smaller than {MAVLINK_SYSID_MAX}") - @patch('builtins.print') + @patch("builtins.print") def test_output_params_qgcs_COMPID_INVALID(self, _mock_print): # pylint: disable=invalid-name # Prepare a dummy defaults dictionary - defaults = {'PARAM2': 2.0, 'PARAM1': 1.0} + defaults = {"PARAM2": 2.0, "PARAM1": 1.0} # Assert that a SystemExit is raised with the correct message when an invalid compid is used with self.assertRaises(SystemExit) as cm: - defaults = sort_params(defaults, 'qgcs') - output_params(defaults, 'qgcs', -1, -3) + defaults = sort_params(defaults, "qgcs") + output_params(defaults, "qgcs", -1, -3) self.assertEqual(str(cm.exception), "Invalid component ID parameter -3 must not be negative") # Assert that a SystemExit is raised with the correct message when an invalid compid is used with self.assertRaises(SystemExit) as cm: - defaults = sort_params(defaults, 'qgcs') - output_params(defaults, 'qgcs', 1, MAVLINK_COMPID_MAX+3) + defaults = sort_params(defaults, "qgcs") + output_params(defaults, "qgcs", 1, MAVLINK_COMPID_MAX + 3) self.assertEqual(str(cm.exception), f"Invalid component ID parameter 259 must be smaller than {MAVLINK_COMPID_MAX}") - @patch('builtins.print') + @patch("builtins.print") def test_output_params_integer(self, mock_print): # Prepare a dummy defaults dictionary with an integer value - defaults = {'PARAM1': 1.01, 'PARAM2': 2.00} + defaults = {"PARAM1": 1.01, "PARAM2": 2.00} # Call the function with the dummy dictionary, 'missionplanner' format type and 'missionplanner' sort type - defaults = sort_params(defaults, 'missionplanner') - output_params(defaults, 'missionplanner') + defaults = sort_params(defaults, "missionplanner") + output_params(defaults, "missionplanner") # Check if the print function was called with the correct parameters - expected_calls = [unittest.mock.call('PARAM1,1.01'), unittest.mock.call('PARAM2,2')] + expected_calls = [unittest.mock.call("PARAM1,1.01"), unittest.mock.call("PARAM2,2")] mock_print.assert_has_calls(expected_calls, any_order=False) - -if __name__ == '__main__': +if __name__ == "__main__": unittest.main() diff --git a/unittests/frontend_tkinter_test.py b/unittests/frontend_tkinter_test.py index 4727879..81bcec2 100755 --- a/unittests/frontend_tkinter_test.py +++ b/unittests/frontend_tkinter_test.py @@ -1,26 +1,26 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" # pylint: skip-file -import unittest -from unittest.mock import patch, MagicMock import tkinter as tk -from MethodicConfigurator.frontend_tkinter_base import show_error_message -from MethodicConfigurator.frontend_tkinter_base import show_tooltip +import unittest +from unittest.mock import MagicMock, patch + +from MethodicConfigurator.frontend_tkinter_base import show_error_message, show_tooltip class TestShowErrorMessage(unittest.TestCase): # pylint: disable=missing-class-docstring - @patch('tkinter.messagebox.showerror') - @patch('tkinter.Tk') - @patch('tkinter.ttk.Style') # Mock the ttk.Style class + @patch("tkinter.messagebox.showerror") + @patch("tkinter.Tk") + @patch("tkinter.ttk.Style") # Mock the ttk.Style class def test_show_error_message(self, mock_style, mock_tk, mock_showerror): # Mock the Tkinter Tk class to prevent it from actually creating a window mock_tk.return_value.withdraw.return_value = None @@ -43,8 +43,8 @@ def test_show_error_message(self, mock_style, mock_tk, mock_showerror): class TestShowTooltip(unittest.TestCase): - @patch('tkinter.Toplevel') - @patch('tkinter.ttk.Label') + @patch("tkinter.Toplevel") + @patch("tkinter.ttk.Label") def test_show_tooltip(self, mock_label, mock_toplevel): # Mock the Tkinter Toplevel class to prevent it from actually creating a window mock_toplevel.return_value.deiconify.return_value = None @@ -73,8 +73,14 @@ def test_show_tooltip(self, mock_label, mock_toplevel): mock_toplevel.assert_called_once() # Assert that the Tkinter Label class was instantiated with the correct parameters - mock_label.assert_called_once_with(mock_toplevel.return_value, text="Test Tooltip Message", - background="#ffffe0", relief="solid", borderwidth=1, justify=tk.LEFT) + mock_label.assert_called_once_with( + mock_toplevel.return_value, + text="Test Tooltip Message", + background="#ffffe0", + relief="solid", + borderwidth=1, + justify=tk.LEFT, + ) # Assert that the Tkinter Toplevel instance's deiconify method was called # mock_toplevel.return_value.deiconify.assert_called() @@ -86,5 +92,5 @@ def test_show_tooltip(self, mock_label, mock_toplevel): mock_label.return_value.pack.assert_called_once() -if __name__ == '__main__': +if __name__ == "__main__": unittest.main() diff --git a/unittests/middleware_template_overview_test.py b/unittests/middleware_template_overview_test.py index 84c0aa4..4e30ea0 100644 --- a/unittests/middleware_template_overview_test.py +++ b/unittests/middleware_template_overview_test.py @@ -1,33 +1,24 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" import unittest + from MethodicConfigurator.middleware_template_overview import TemplateOverview class TestTemplateOverview(unittest.TestCase): # pylint: disable=missing-class-docstring - def setUp(self): # Define sample data to be used in tests self.sample_data = { - 'Flight Controller': { - 'Product': { - 'Manufacturer': 'ArduPilot', - 'Model': 'Pixhawk4' - } - }, - 'Frame': { - 'Specifications': { - 'TOW max Kg': '5' - } - }, + "Flight Controller": {"Product": {"Manufacturer": "ArduPilot", "Model": "Pixhawk4"}}, + "Frame": {"Specifications": {"TOW max Kg": "5"}}, # ... add other components as per your structure } @@ -36,9 +27,9 @@ def test_template_overview_initialization(self): template_overview = TemplateOverview(self.sample_data) # Check if attributes are set correctly - self.assertEqual(template_overview.fc_manufacturer, 'ArduPilot') - self.assertEqual(template_overview.fc_model, 'Pixhawk4') - self.assertEqual(template_overview.tow_max_kg, '5') + self.assertEqual(template_overview.fc_manufacturer, "ArduPilot") + self.assertEqual(template_overview.fc_model, "Pixhawk4") + self.assertEqual(template_overview.tow_max_kg, "5") # .. similarly test other attributes def test_template_overview_column_labels(self): @@ -68,18 +59,18 @@ def test_template_overview_attributes_method(self): # Check if the attribute keys match the expected set of attributes expected_attributes = { - 'fc_manufacturer', - 'fc_model', - 'tow_max_kg', - 'prop_diameter_inches', - 'rc_protocol', - 'telemetry_model', - 'esc_protocol', - 'gnss_model', - 'gnss_connection', + "fc_manufacturer", + "fc_model", + "tow_max_kg", + "prop_diameter_inches", + "rc_protocol", + "telemetry_model", + "esc_protocol", + "gnss_model", + "gnss_connection", } self.assertEqual(expected_attributes, set(attribute_keys)) -if __name__ == '__main__': +if __name__ == "__main__": unittest.main() diff --git a/unittests/param_pid_adjustment_update_test.py b/unittests/param_pid_adjustment_update_test.py index 0066a3d..59c4340 100755 --- a/unittests/param_pid_adjustment_update_test.py +++ b/unittests/param_pid_adjustment_update_test.py @@ -1,6 +1,6 @@ #!/usr/bin/python3 -''' +""" This script updates the PID adjustment parameters to be factor of the corresponding autotuned or optimized parameters. Usage: @@ -11,18 +11,16 @@ SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" # pylint: skip-file -import unittest import argparse import os import shutil +import unittest -from MethodicConfigurator.param_pid_adjustment_update import ranged_type -from MethodicConfigurator.param_pid_adjustment_update import Par -from MethodicConfigurator.param_pid_adjustment_update import update_pid_adjustment_params +from MethodicConfigurator.param_pid_adjustment_update import Par, ranged_type, update_pid_adjustment_params class TestRangedType(unittest.TestCase): @@ -38,294 +36,310 @@ def test_invalid_input(self): ranged_type(float, 0.1, 0.8)(0.9) self.assertEqual(cm.exception.args[0], "must be within [0.1, 0.8]") with self.assertRaises(argparse.ArgumentTypeError) as cm: - ranged_type(float, 0.1, 0.8)('sf') + ranged_type(float, 0.1, 0.8)("sf") self.assertEqual(cm.exception.args[0], "must be a valid ") class TestLoadParamFileIntoDict(unittest.TestCase): def test_valid_input(self): # Create a temporary file with valid parameter data - with open('temp.param', 'w', encoding='utf-8') as f: - f.write('PARAM1 1.0\n') - f.write('# PARAM2 2.0\n') - f.write('PARAM3 3.0 # Comment\n') + with open("temp.param", "w", encoding="utf-8") as f: + f.write("PARAM1 1.0\n") + f.write("# PARAM2 2.0\n") + f.write("PARAM3 3.0 # Comment\n") # Call the function and check the result - params, _ = Par.load_param_file_into_dict('temp.param') + params, _ = Par.load_param_file_into_dict("temp.param") self.assertEqual(len(params), 2) - self.assertEqual(params['PARAM1'].value, 1.0) - self.assertEqual(params['PARAM3'].value, 3.0) + self.assertEqual(params["PARAM1"].value, 1.0) + self.assertEqual(params["PARAM3"].value, 3.0) def test_invalid_input(self): # Create a temporary file with invalid parameter data - with open('temp.param', 'w', encoding='utf-8') as f: - f.write('PARAM1 1.0\n') - f.write('PARAM2\n') # Missing value - f.write('PARAM3 3.0 # Invalid comment\n') + with open("temp.param", "w", encoding="utf-8") as f: + f.write("PARAM1 1.0\n") + f.write("PARAM2\n") # Missing value + f.write("PARAM3 3.0 # Invalid comment\n") # Call the function and check that it raises an exception with self.assertRaises(SystemExit) as cm: - Par.load_param_file_into_dict('temp.param') + Par.load_param_file_into_dict("temp.param") self.assertEqual(cm.exception.args[0], "Missing parameter-value separator: PARAM2 in temp.param line 2") def test_empty_file(self): # Create an empty temporary file - with open('temp.param', 'w', encoding='utf-8') as f: # noqa F841 + with open("temp.param", "w", encoding="utf-8") as f: # noqa F841 pass # Call the function and check the result - params, _ = Par.load_param_file_into_dict('temp.param') + params, _ = Par.load_param_file_into_dict("temp.param") self.assertEqual(len(params), 0) def test_only_comments(self): # Create a temporary file with only comments - with open('temp.param', 'w', encoding='utf-8') as f: - f.write('# Comment 1\n') - f.write('# Comment 2\n') + with open("temp.param", "w", encoding="utf-8") as f: + f.write("# Comment 1\n") + f.write("# Comment 2\n") # Call the function and check the result - params, _ = Par.load_param_file_into_dict('temp.param') + params, _ = Par.load_param_file_into_dict("temp.param") self.assertEqual(len(params), 0) def test_missing_value(self): # Create a temporary file with a missing value - with open('temp.param', 'w', encoding='utf-8') as f: - f.write('PARAM1\n') + with open("temp.param", "w", encoding="utf-8") as f: + f.write("PARAM1\n") # Call the function and check that it raises an exception with self.assertRaises(SystemExit) as cm: - Par.load_param_file_into_dict('temp.param') + Par.load_param_file_into_dict("temp.param") self.assertEqual(cm.exception.args[0], "Missing parameter-value separator: PARAM1 in temp.param line 1") def test_space_separator(self): # Create a temporary file with a space as the separator - with open('temp.param', 'w', encoding='utf-8') as f: - f.write('PARAM1 1.0\n') + with open("temp.param", "w", encoding="utf-8") as f: + f.write("PARAM1 1.0\n") # Call the function and check the result - params, _ = Par.load_param_file_into_dict('temp.param') - self.assertEqual(params['PARAM1'].value, 1.0) + params, _ = Par.load_param_file_into_dict("temp.param") + self.assertEqual(params["PARAM1"].value, 1.0) def test_comma_separator(self): # Create a temporary file with a comma as the separator - with open('temp.param', 'w', encoding='utf-8') as f: - f.write('PARAM1,1.0\n') + with open("temp.param", "w", encoding="utf-8") as f: + f.write("PARAM1,1.0\n") # Call the function and check the result - params, _ = Par.load_param_file_into_dict('temp.param') - self.assertEqual(params['PARAM1'].value, 1.0) + params, _ = Par.load_param_file_into_dict("temp.param") + self.assertEqual(params["PARAM1"].value, 1.0) def test_tab_separator(self): # Create a temporary file with a tab as the separator - with open('temp.param', 'w', encoding='utf-8') as f: - f.write('PARAM1\t1.0\n') + with open("temp.param", "w", encoding="utf-8") as f: + f.write("PARAM1\t1.0\n") # Call the function and check the result - params, _ = Par.load_param_file_into_dict('temp.param') - self.assertEqual(params['PARAM1'].value, 1.0) + params, _ = Par.load_param_file_into_dict("temp.param") + self.assertEqual(params["PARAM1"].value, 1.0) def test_invalid_characters(self): # Create a temporary file with invalid characters in the parameter name - with open('temp.param', 'w', encoding='utf-8') as f: - f.write('PARAM-1 1.0\n') + with open("temp.param", "w", encoding="utf-8") as f: + f.write("PARAM-1 1.0\n") # Call the function and check that it raises an exception with self.assertRaises(SystemExit) as cm: - Par.load_param_file_into_dict('temp.param') + Par.load_param_file_into_dict("temp.param") self.assertEqual(cm.exception.args[0], "Invalid characters in parameter name PARAM-1 in temp.param line 1") def test_long_parameter_name(self): # Create a temporary file with a too long parameter name - with open('temp.param', 'w', encoding='utf-8') as f: - f.write('PARAMETER_THAT_IS_TOO_LONG 1.0\n') + with open("temp.param", "w", encoding="utf-8") as f: + f.write("PARAMETER_THAT_IS_TOO_LONG 1.0\n") # Call the function and check that it raises an exception with self.assertRaises(SystemExit) as cm: - Par.load_param_file_into_dict('temp.param') + Par.load_param_file_into_dict("temp.param") self.assertEqual(cm.exception.args[0], "Too long parameter name: PARAMETER_THAT_IS_TOO_LONG in temp.param line 1") def test_invalid_value(self): # Create a temporary file with an invalid value - with open('temp.param', 'w', encoding='utf-8') as f: - f.write('PARAM1 VALUE\n') + with open("temp.param", "w", encoding="utf-8") as f: + f.write("PARAM1 VALUE\n") # Call the function and check that it raises an exception with self.assertRaises(SystemExit) as cm: - Par.load_param_file_into_dict('temp.param') + Par.load_param_file_into_dict("temp.param") self.assertEqual(cm.exception.args[0], "Invalid parameter value VALUE in temp.param line 1") def test_duplicated_parameter(self): # Create a temporary file with duplicated parameters - with open('temp.param', 'w', encoding='utf-8') as f: - f.write('PARAM1 1.0\n') - f.write('PARAM1 2.0\n') + with open("temp.param", "w", encoding="utf-8") as f: + f.write("PARAM1 1.0\n") + f.write("PARAM1 2.0\n") # Call the function and check that it raises an exception with self.assertRaises(SystemExit) as cm: - Par.load_param_file_into_dict('temp.param') + Par.load_param_file_into_dict("temp.param") self.assertEqual(cm.exception.args[0], "Duplicated parameter PARAM1 in temp.param line 2") def tearDown(self): # Remove the temporary file after each test - if os.path.exists('temp.param'): - os.remove('temp.param') + if os.path.exists("temp.param"): + os.remove("temp.param") class TestExportToParam(unittest.TestCase): def test_valid_input(self): # Create a temporary file with valid parameter data - with open('temp.param', 'w', encoding='utf-8') as f: - f.write('PARAM1 1.0\n') - f.write('PARAM2 2.0\n') - f.write('PARAM3 3.0 # Comment\n') + with open("temp.param", "w", encoding="utf-8") as f: + f.write("PARAM1 1.0\n") + f.write("PARAM2 2.0\n") + f.write("PARAM3 3.0 # Comment\n") # Load the parameters into a dictionary - params, _ = Par.load_param_file_into_dict('temp.param') + params, _ = Par.load_param_file_into_dict("temp.param") # Export the parameters to a file - Par.export_to_param(params, 'output.param') + Par.export_to_param(params, "output.param") # Check the contents of the output file - with open('output.param', 'r', encoding='utf-8') as f: + with open("output.param", "r", encoding="utf-8") as f: output = f.read() - self.assertEqual(output, 'PARAM1,1\nPARAM2,2\nPARAM3,3 # Comment\n') + self.assertEqual(output, "PARAM1,1\nPARAM2,2\nPARAM3,3 # Comment\n") def test_with_header(self): # Create a temporary file with valid parameter data - with open('temp.param', 'w', encoding='utf-8') as f: - f.write('# HEADER\n') - f.write('PARAM1 1.0\n') - f.write('PARAM2 2.0\n') - f.write('PARAM3 3.0\n') + with open("temp.param", "w", encoding="utf-8") as f: + f.write("# HEADER\n") + f.write("PARAM1 1.0\n") + f.write("PARAM2 2.0\n") + f.write("PARAM3 3.0\n") # Load the parameters into a dictionary - params, _ = Par.load_param_file_into_dict('temp.param') + params, _ = Par.load_param_file_into_dict("temp.param") # Export the parameters to a file, including the header - Par.export_to_param(params, 'output.param', ['# HEADER']) + Par.export_to_param(params, "output.param", ["# HEADER"]) # Check the contents of the output file - with open('output.param', 'r', encoding='utf-8') as f: + with open("output.param", "r", encoding="utf-8") as f: output = f.read() - self.assertEqual(output, '# HEADER\nPARAM1,1\nPARAM2,2\nPARAM3,3\n') + self.assertEqual(output, "# HEADER\nPARAM1,1\nPARAM2,2\nPARAM3,3\n") def tearDown(self): # Remove the temporary files after each test - if os.path.exists('temp.param'): - os.remove('temp.param') - if os.path.exists('output.param'): - os.remove('output.param') + if os.path.exists("temp.param"): + os.remove("temp.param") + if os.path.exists("output.param"): + os.remove("output.param") class TestUpdatePidAdjustmentParams(unittest.TestCase): def setUp(self): # Create a directory for the test files - self.test_dir = 'test_directory' + self.test_dir = "test_directory" os.mkdir(self.test_dir) # Create a default, adjustment and optimized parameter file for testing - self.default_param_file = os.path.join(self.test_dir, '00_default.param') - self.adjustment_param_file = os.path.join(self.test_dir, '16_pid_adjustment.param') - self.optimized_param_file = os.path.join(self.test_dir, 'optimized_parameter_file.param') - with open(self.default_param_file, 'w', encoding='utf-8') as f: - f.write('PARAM1,1.0\nPARAM2,2.0\nPARAM3,3.0\n') - with open(self.adjustment_param_file, 'w', encoding='utf-8') as f: - f.write('PARAM1,1.5\nPARAM2,2.5\nPARAM3,3.5\n') - with open(self.optimized_param_file, 'w', encoding='utf-8') as f: - f.write('PARAM1,1.5\nPARAM2,2.5\nPARAM3,3.5\n') + self.default_param_file = os.path.join(self.test_dir, "00_default.param") + self.adjustment_param_file = os.path.join(self.test_dir, "16_pid_adjustment.param") + self.optimized_param_file = os.path.join(self.test_dir, "optimized_parameter_file.param") + with open(self.default_param_file, "w", encoding="utf-8") as f: + f.write("PARAM1,1.0\nPARAM2,2.0\nPARAM3,3.0\n") + with open(self.adjustment_param_file, "w", encoding="utf-8") as f: + f.write("PARAM1,1.5\nPARAM2,2.5\nPARAM3,3.5\n") + with open(self.optimized_param_file, "w", encoding="utf-8") as f: + f.write("PARAM1,1.5\nPARAM2,2.5\nPARAM3,3.5\n") def test_all_parameters_present(self): # Remove a parameter from the default parameter file - with open(self.default_param_file, 'w', encoding='utf-8') as f: - f.write('PARAM1,1.0\nPARAM3,3.0\n') + with open(self.default_param_file, "w", encoding="utf-8") as f: + f.write("PARAM1,1.0\nPARAM3,3.0\n") # Call the function and expect a SystemExit exception with self.assertRaises(SystemExit) as cm: update_pid_adjustment_params(self.test_dir, os.path.basename(self.optimized_param_file), 0.5) # Assert that the error message is as expected - self.assertEqual(cm.exception.args[0], f"Parameter PARAM2 is not present in {os.path.join('test_directory','00_default.param')}") + self.assertEqual( + cm.exception.args[0], f"Parameter PARAM2 is not present in {os.path.join('test_directory','00_default.param')}" + ) def test_parameter_missing_from_default_file(self): # A parameter is missing from the default parameter file - with open(self.default_param_file, 'w', encoding='utf-8') as f: - f.write('PARAM1,1.0\nPARAM3,3.0\n') + with open(self.default_param_file, "w", encoding="utf-8") as f: + f.write("PARAM1,1.0\nPARAM3,3.0\n") with self.assertRaises(SystemExit) as cm: update_pid_adjustment_params(self.test_dir, os.path.basename(self.optimized_param_file), 0.5) - self.assertEqual(cm.exception.args[0], f"Parameter PARAM2 is not present in {os.path.join('test_directory','00_default.param')}") + self.assertEqual( + cm.exception.args[0], f"Parameter PARAM2 is not present in {os.path.join('test_directory','00_default.param')}" + ) def test_parameter_missing_from_optimized_file(self): # A parameter is missing from the optimized parameter file - with open(self.optimized_param_file, 'w', encoding='utf-8') as f: - f.write('PARAM1,1.5\nPARAM3,3.5\n') + with open(self.optimized_param_file, "w", encoding="utf-8") as f: + f.write("PARAM1,1.5\nPARAM3,3.5\n") with self.assertRaises(SystemExit) as cm: update_pid_adjustment_params(self.test_dir, os.path.basename(self.optimized_param_file), 0.5) - self.assertEqual(cm.exception.args[0], - f"Parameter PARAM2 is not present in {os.path.join('test_directory','optimized_parameter_file.param')}") + self.assertEqual( + cm.exception.args[0], + f"Parameter PARAM2 is not present in {os.path.join('test_directory','optimized_parameter_file.param')}", + ) def test_empty_files(self): # Both the default and optimized parameter files are empty - with open(self.default_param_file, 'w', encoding='utf-8') as f: # noqa F841 + with open(self.default_param_file, "w", encoding="utf-8") as f: # F841 pass - with open(self.optimized_param_file, 'w', encoding='utf-8') as f: # noqa F841 + with open(self.optimized_param_file, "w", encoding="utf-8") as f: # noqa F841 pass with self.assertRaises(SystemExit) as cm: update_pid_adjustment_params(self.test_dir, os.path.basename(self.optimized_param_file), 0.5) - self.assertEqual(cm.exception.args[0], f"Failed to load default parameters from {os.path.join('test_directory','00_default.param')}") + self.assertEqual( + cm.exception.args[0], f"Failed to load default parameters from {os.path.join('test_directory','00_default.param')}" + ) def test_empty_default_file(self): # Create an empty default parameter file - with open(self.default_param_file, 'w', encoding='utf-8') as f: # noqa F841 + with open(self.default_param_file, "w", encoding="utf-8") as f: # noqa F841 pass with self.assertRaises(SystemExit) as cm: update_pid_adjustment_params(self.test_dir, os.path.basename(self.optimized_param_file), 0.5) - self.assertEqual(cm.exception.args[0], f"Failed to load default parameters from {os.path.join('test_directory','00_default.param')}") + self.assertEqual( + cm.exception.args[0], f"Failed to load default parameters from {os.path.join('test_directory','00_default.param')}" + ) def test_empty_optimized_file(self): # Create an empty optimized parameter file - with open(self.optimized_param_file, 'w', encoding='utf-8') as f: # noqa F841 + with open(self.optimized_param_file, "w", encoding="utf-8") as f: # noqa F841 pass with self.assertRaises(SystemExit) as cm: update_pid_adjustment_params(self.test_dir, os.path.basename(self.optimized_param_file), 0.5) - self.assertEqual(cm.exception.args[0], - f"Failed to load optimized parameters from {os.path.join('test_directory','optimized_parameter_file.param')}") + self.assertEqual( + cm.exception.args[0], + f"Failed to load optimized parameters from {os.path.join('test_directory','optimized_parameter_file.param')}", + ) def test_empty_adjustment_file(self): # Create an empty adjustment parameter file - with open(self.adjustment_param_file, 'w', encoding='utf-8') as f: # noqa F841 + with open(self.adjustment_param_file, "w", encoding="utf-8") as f: # noqa F841 pass with self.assertRaises(SystemExit) as cm: update_pid_adjustment_params(self.test_dir, os.path.basename(self.optimized_param_file), 0.5) - self.assertEqual(cm.exception.args[0], - f"Failed to load PID adjustment parameters from {os.path.join('test_directory','16_pid_adjustment.param')}") + self.assertEqual( + cm.exception.args[0], + f"Failed to load PID adjustment parameters from {os.path.join('test_directory','16_pid_adjustment.param')}", + ) def test_zero_default_value(self): # Set a parameter in the default parameter file to zero - with open(self.default_param_file, 'w', encoding='utf-8') as f: - f.write('PARAM1,0.0\nPARAM2,2.0\nPARAM3,3.0\n') + with open(self.default_param_file, "w", encoding="utf-8") as f: + f.write("PARAM1,0.0\nPARAM2,2.0\nPARAM3,3.0\n") # Call the function - pid_adjustment_params_dict, _pid_adjustment_file_path, _content_header = \ - update_pid_adjustment_params(self.test_dir, os.path.basename(self.optimized_param_file), 0.5) + pid_adjustment_params_dict, _pid_adjustment_file_path, _content_header = update_pid_adjustment_params( + self.test_dir, os.path.basename(self.optimized_param_file), 0.5 + ) # Assert that the PID adjustment parameter value is zero - self.assertEqual(pid_adjustment_params_dict['PARAM1'].value, 0) + self.assertEqual(pid_adjustment_params_dict["PARAM1"].value, 0) def test_update_comment(self): # Set a parameter in the default parameter file - with open(self.default_param_file, 'w', encoding='utf-8') as f: - f.write('PARAM1,1.0\nPARAM2,2.0\nPARAM3,3.0\n') + with open(self.default_param_file, "w", encoding="utf-8") as f: + f.write("PARAM1,1.0\nPARAM2,2.0\nPARAM3,3.0\n") # Call the function - pid_adjustment_params_dict, _, _ = \ - update_pid_adjustment_params(self.test_dir, os.path.basename(self.optimized_param_file), 0.5) + pid_adjustment_params_dict, _, _ = update_pid_adjustment_params( + self.test_dir, os.path.basename(self.optimized_param_file), 0.5 + ) # Assert that the comment is updated correctly - self.assertEqual(pid_adjustment_params_dict['PARAM1'].comment, " = 0.75 * (1 default)") + self.assertEqual(pid_adjustment_params_dict["PARAM1"].comment, " = 0.75 * (1 default)") def tearDown(self): # Remove the test directory after each test shutil.rmtree(self.test_dir) -if __name__ == '__main__': +if __name__ == "__main__": unittest.main() diff --git a/unittests/version_test.py b/unittests/version_test.py index c6b61d8..ae3af37 100644 --- a/unittests/version_test.py +++ b/unittests/version_test.py @@ -1,18 +1,19 @@ #!/usr/bin/env python3 -''' +""" This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" -import unittest import re +import unittest from MethodicConfigurator.version import VERSION + class TestVersion(unittest.TestCase): """ Test that the VERSION constant is a string and follows semantic versioning. @@ -20,11 +21,11 @@ class TestVersion(unittest.TestCase): def test_version_format(self): # Semantic versioning pattern - semver_pattern = r'^\d+\.\d+\.\d+$' + semver_pattern = r"^\d+\.\d+\.\d+$" match = re.match(semver_pattern, VERSION) msg = f"VERSION string '{VERSION}' does not follow semantic versioning" self.assertIsNotNone(match, msg) -if __name__ == '__main__': +if __name__ == "__main__": unittest.main() diff --git a/windows/return_version.py b/windows/return_version.py index 76a5a47..4204ad3 100755 --- a/windows/return_version.py +++ b/windows/return_version.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 -''' +""" This script returns the current version number Used as part of building the Windows setup file (MethodicConfiguratorWinBuild.bat) @@ -9,7 +9,7 @@ SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas SPDX-License-Identifier: GPL-3.0-or-later -''' +""" # It assumes there is a line like this: # VERSION = "12344" @@ -18,9 +18,9 @@ # print(VERSION) # glob supports Unix style pathname extensions -with open("../MethodicConfigurator/version.py", encoding='utf-8') as f: +with open("../MethodicConfigurator/version.py", encoding="utf-8") as f: searchlines = f.readlines() for i, line in enumerate(searchlines): if "VERSION = " in line: - print(line[11:len(line)-2]) + print(line[11 : len(line) - 2]) break