Skip to content

Commit

Permalink
IMPROVEMENT: Drop support for python 3.9
Browse files Browse the repository at this point in the history
  • Loading branch information
amilcarlucas committed Nov 14, 2024
1 parent 0c4e0f5 commit bd7e071
Show file tree
Hide file tree
Showing 14 changed files with 62 additions and 73 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/pylint.yml
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ jobs:
runs-on: ubuntu-latest
strategy:
matrix:
python-version: ["3.8", "3.11"]
python-version: ["3.9", "3.11"]
steps:

- name: Checkout
Expand Down
36 changes: 18 additions & 18 deletions MethodicConfigurator/annotate_params.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
from sys import exc_info as sys_exc_info
from sys import exit as sys_exit
from types import TracebackType
from typing import Any, Dict, List, Optional, Tuple
from typing import Any, Optional
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
Expand Down Expand Up @@ -141,7 +141,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.
Expand All @@ -151,7 +151,7 @@ def load_param_file_into_dict(param_file: str) -> Dict[str, "Par"]:
Returns:
dict: A dictionary containing the parameters from the file.
"""
parameter_dict: Dict[str, Par] = {}
parameter_dict: dict[str, Par] = {}
try:
with open(param_file, encoding="utf-8") as f_handle:
for i, f_line in enumerate(f_handle, start=1):
Expand Down Expand Up @@ -202,7 +202,7 @@ def validate_parameter(param_file, parameter_dict, i, original_line, comment, pa
raise SystemExit(f"Caused by line {i} of file {param_file}: {original_line}") from exc

@staticmethod
def missionplanner_sort(item: str) -> Tuple[str, ...]:
def missionplanner_sort(item: str) -> tuple[str, ...]:
"""
Sorts a parameter name according to the rules defined in the Mission Planner software.
Expand All @@ -217,7 +217,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.
Expand Down Expand Up @@ -266,7 +266,7 @@ def format_params(param_dict: Dict[str, "Par"], file_format: str = "missionplann
return formatted_params

@staticmethod
def export_to_param(formatted_params: List[str], filename_out: str) -> None:
def export_to_param(formatted_params: list[str], filename_out: str) -> None:
"""
Exports a list of formatted parameters to an ArduPilot parameter file.
Expand All @@ -288,7 +288,7 @@ def export_to_param(formatted_params: List[str], filename_out: str) -> None:
raise SystemExit(f"ERROR: writing to file {filename_out}: {e}") from e

@staticmethod
def print_out(formatted_params: List[str], name: str) -> None:
def print_out(formatted_params: list[str], name: str) -> None:
"""
Print out the contents of the provided list.
If the list is too large, print only the ones that fit on the screen and
Expand Down Expand Up @@ -389,8 +389,8 @@ def get_xml_data(base_url: str, directory: str, filename: str, vehicle_type: str
return DET.fromstring(xml_data)


def load_default_param_file(directory: str) -> Dict[str, "Par"]:
param_default_dict: Dict[str, Par] = {}
def load_default_param_file(directory: str) -> dict[str, "Par"]:
param_default_dict: dict[str, Par] = {}
# 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"))
Expand All @@ -416,7 +416,7 @@ def remove_prefix(text: str, prefix: str) -> str:
return text


def split_into_lines(string_to_split: str, maximum_line_length: int) -> List[str]:
def split_into_lines(string_to_split: str, maximum_line_length: int) -> list[str]:
"""
Splits a string into lines of a maximum length.
Expand All @@ -432,7 +432,7 @@ def split_into_lines(string_to_split: str, maximum_line_length: int) -> List[str
return [line.rstrip() for line in doc_lines]


def create_doc_dict(root: ET.Element, vehicle_type: str, max_line_length: int = 100) -> Dict[str, Any]:
def create_doc_dict(root: ET.Element, vehicle_type: str, max_line_length: int = 100) -> dict[str, Any]:
"""
Create a dictionary of parameter documentation from the root element of the parsed XML data.
Expand All @@ -443,7 +443,7 @@ def create_doc_dict(root: ET.Element, vehicle_type: str, max_line_length: int =
Dict[str, Any]: A dictionary of parameter documentation.
"""
# Dictionary to store the parameter documentation
doc: Dict[str, Any] = {}
doc: dict[str, Any] = {}

# Use the findall method with an XPath expression to find all "param" elements
for param in root.findall(".//param"):
Expand All @@ -457,7 +457,7 @@ def create_doc_dict(root: ET.Element, vehicle_type: str, max_line_length: int =

human_name = param.get("humanName")
documentation = param.get("documentation")
documentation_lst: List[str] = []
documentation_lst: list[str] = []
if documentation:
documentation_lst = split_into_lines(documentation, max_line_length)
# the keys are the "name" attribute of the "field" sub-elements
Expand Down Expand Up @@ -488,7 +488,7 @@ def create_doc_dict(root: ET.Element, vehicle_type: str, max_line_length: int =
return doc


def format_columns(values: Dict[str, Any], max_width: int = 105, max_columns: int = 4) -> List[str]:
def format_columns(values: dict[str, Any], max_width: int = 105, max_columns: int = 4) -> list[str]:
"""
Formats a dictionary of values into column-major horizontally aligned columns.
It uses at most max_columns columns
Expand Down Expand Up @@ -545,7 +545,7 @@ def extract_parameter_name(item: str) -> str:
return match.group(0) if match else item


def missionplanner_sort(item: str) -> Tuple[str, ...]:
def missionplanner_sort(item: str) -> tuple[str, ...]:
"""
MissionPlanner parameter sorting function
"""
Expand Down Expand Up @@ -584,10 +584,10 @@ def extract_parameter_name_and_validate(line: str, filename: str, line_nr: int)


def update_parameter_documentation(
doc: Dict[str, Any],
doc: dict[str, Any],
target: str = ".",
sort_type: str = "none",
param_default_dict: Optional[Dict] = None,
param_default_dict: Optional[dict] = None,
delete_documentation_annotations=False,
) -> None:
"""
Expand Down Expand Up @@ -742,7 +742,7 @@ def get_xml_url(vehicle_type: str, firmware_version: str) -> str:

def parse_parameter_metadata(
xml_url: str, xml_dir: str, xml_file: str, vehicle_type: str, max_line_length: int
) -> Dict[str, Any]:
) -> 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)

Expand Down
3 changes: 1 addition & 2 deletions MethodicConfigurator/ardupilot_methodic_configurator.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
from logging import getLevelName as logging_getLevelName
from logging import info as logging_info
from sys import exit as sys_exit
from typing import Tuple

from MethodicConfigurator import _, __version__
from MethodicConfigurator.backend_filesystem import LocalFilesystem
Expand Down Expand Up @@ -61,7 +60,7 @@ def argument_parser():
return add_common_arguments_and_parse(parser)


def connect_to_fc_and_read_parameters(args) -> Tuple[FlightController, str]:
def connect_to_fc_and_read_parameters(args) -> tuple[FlightController, str]:
flight_controller = FlightController(args.reboot_time)

error_str = flight_controller.connect(args.device, log_errors=False)
Expand Down
34 changes: 17 additions & 17 deletions MethodicConfigurator/backend_filesystem.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
from re import compile as re_compile
from shutil import copy2 as shutil_copy2
from shutil import copytree as shutil_copytree
from typing import Any, Dict, List, Tuple
from typing import Any
from zipfile import ZipFile

from requests import get as requests_get
Expand Down Expand Up @@ -82,16 +82,16 @@ class LocalFilesystem(VehicleComponents, ConfigurationSteps, ProgramSettings):
"""

def __init__(self, vehicle_dir: str, vehicle_type: str, fw_version: str, allow_editing_template_files: bool):
self.file_parameters: Dict[str, Dict[str, Par]] = {}
self.file_parameters: dict[str, dict[str, Par]] = {}
VehicleComponents.__init__(self)
ConfigurationSteps.__init__(self, vehicle_dir, vehicle_type)
ProgramSettings.__init__(self)
self.vehicle_type = vehicle_type
self.fw_version = fw_version
self.allow_editing_template_files = allow_editing_template_files
self.param_default_dict: Dict[str, Par] = {}
self.param_default_dict: dict[str, Par] = {}
self.vehicle_dir = vehicle_dir
self.doc_dict: Dict[str, Any] = {}
self.doc_dict: dict[str, Any] = {}
if vehicle_dir is not None:
self.re_init(vehicle_dir, vehicle_type)

Expand Down Expand Up @@ -215,7 +215,7 @@ def __extend_and_reformat_parameter_documentation_metadata(self): # pylint: dis
prefix_parts += [f"Default: {default_value}"]
param_info["doc_tooltip"] = ("\n").join(prefix_parts)

def read_params_from_files(self) -> Dict[str, Dict[str, "Par"]]:
def read_params_from_files(self) -> dict[str, dict[str, "Par"]]:
"""
Reads intermediate parameter files from a directory and stores their contents in a dictionary.
Expand All @@ -227,7 +227,7 @@ def read_params_from_files(self) -> Dict[str, Dict[str, "Par"]]:
- Dict[str, Dict[str, 'Par']]: A dictionary with filenames as keys and as values
a dictionary with (parameter names, values) pairs.
"""
parameters: Dict[str, Dict[str, Par]] = {}
parameters: dict[str, dict[str, Par]] = {}
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$")
Expand Down Expand Up @@ -261,7 +261,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.
Expand Down Expand Up @@ -293,7 +293,7 @@ def vehicle_configuration_file_exists(self, filename: str) -> bool:
os_path.join(self.vehicle_dir, filename)
)

def __all_intermediate_parameter_file_comments(self) -> Dict[str, str]:
def __all_intermediate_parameter_file_comments(self) -> dict[str, str]:
"""
Retrieves all comments associated with parameters from intermediate parameter files.
Expand All @@ -311,7 +311,7 @@ def __all_intermediate_parameter_file_comments(self) -> Dict[str, str]:
ret[param] = info.comment
return ret

def annotate_intermediate_comments_to_param_dict(self, param_dict: Dict[str, float]) -> Dict[str, "Par"]:
def annotate_intermediate_comments_to_param_dict(self, param_dict: dict[str, float]) -> dict[str, "Par"]:
"""
Annotates comments from intermediate parameter files to a parameter value-only dictionary.
Expand All @@ -331,7 +331,7 @@ def annotate_intermediate_comments_to_param_dict(self, param_dict: Dict[str, flo
ret[param] = Par(float(value), ip_comments.get(param, ""))
return ret

def categorize_parameters(self, param: Dict[str, "Par"]) -> Tuple[Dict[str, "Par"], Dict[str, "Par"], Dict[str, "Par"]]:
def categorize_parameters(self, param: dict[str, "Par"]) -> tuple[dict[str, "Par"], dict[str, "Par"], dict[str, "Par"]]:
"""
Categorize parameters into three categories based on their default values and documentation attributes.
Expand Down Expand Up @@ -393,7 +393,7 @@ def add_configuration_file_to_zip(self, zipf, filename):
if self.vehicle_configuration_file_exists(filename):
zipf.write(os_path.join(self.vehicle_dir, filename), arcname=filename)

def zip_files(self, files_to_zip: List[Tuple[bool, str]]):
def zip_files(self, files_to_zip: list[tuple[bool, str]]):
"""
Zips the intermediate parameter files that were written to, including specific summary files.
Expand Down Expand Up @@ -469,7 +469,7 @@ def tempcal_imu_result_param_tuple(self):
tempcal_imu_result_param_filename = "03_imu_temperature_calibration_results.param"
return [tempcal_imu_result_param_filename, os_path.join(self.vehicle_dir, tempcal_imu_result_param_filename)]

def copy_fc_values_to_file(self, selected_file: str, params: Dict[str, float]):
def copy_fc_values_to_file(self, selected_file: str, params: dict[str, float]):
ret = 0
if selected_file in self.file_parameters:
for param, v in self.file_parameters[selected_file].items():
Expand Down Expand Up @@ -553,7 +553,7 @@ def get_eval_variables(self):
variables["doc_dict"] = self.doc_dict
return variables

def copy_fc_params_values_to_template_created_vehicle_files(self, fc_parameters: Dict[str, float]):
def copy_fc_params_values_to_template_created_vehicle_files(self, fc_parameters: dict[str, float]):
eval_variables = self.get_eval_variables()
for param_filename, param_dict in self.file_parameters.items():
for param_name, param in param_dict.items():
Expand All @@ -570,18 +570,18 @@ def copy_fc_params_values_to_template_created_vehicle_files(self, fc_parameters:
Par.export_to_param(Par.format_params(param_dict), os_path.join(self.vehicle_dir, param_filename))
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]:
def get_download_url_and_local_filename(self, selected_file: str) -> tuple[str, str]:
if (
selected_file in self.configuration_steps
and "download_file" in self.configuration_steps[selected_file]
Expand All @@ -593,7 +593,7 @@ def get_download_url_and_local_filename(self, selected_file: str) -> Tuple[str,
return src, os_path.join(self.vehicle_dir, dst)
return "", ""

def get_upload_local_and_remote_filenames(self, selected_file: str) -> Tuple[str, str]:
def get_upload_local_and_remote_filenames(self, selected_file: str) -> tuple[str, str]:
if (
selected_file in self.configuration_steps
and "upload_file" in self.configuration_steps[selected_file]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
from logging import info as logging_info
from logging import warning as logging_warning
from os import path as os_path
from typing import Tuple

from MethodicConfigurator import _
from MethodicConfigurator.annotate_params import Par
Expand Down Expand Up @@ -175,7 +174,7 @@ def jump_possible(self, selected_file: str):
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]:
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
if documentation is None:
text = _(
Expand Down
10 changes: 5 additions & 5 deletions MethodicConfigurator/backend_flightcontroller.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
from os import readlink as os_readlink
from time import sleep as time_sleep
from time import time as time_time
from typing import Dict, List, Optional, Tuple
from typing import Optional

import serial.tools.list_ports
import serial.tools.list_ports_common
Expand Down Expand Up @@ -188,7 +188,7 @@ def __request_banner(self):
0,
)

def __receive_banner_text(self) -> List[str]:
def __receive_banner_text(self) -> list[str]:
"""Starts listening for STATUS_TEXT MAVLink messages."""
start_time = time_time()
banner_msgs: list[str] = []
Expand Down Expand Up @@ -324,7 +324,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.
Expand Down Expand Up @@ -352,7 +352,7 @@ def download_params(self, progress_callback=None) -> Tuple[Dict[str, float], Dic
logging_info(_("MAVFTP is not supported by the %s flight controller, fallback to MAVLink"), comport_device)
return self.__download_params_via_mavlink(progress_callback), {}

def __download_params_via_mavlink(self, progress_callback=None) -> Dict[str, float]:
def __download_params_via_mavlink(self, progress_callback=None) -> dict[str, float]:
comport_device = getattr(self.comport, "device", "")
logging_debug(_("Will fetch all parameters from the %s flight controller"), comport_device)

Expand Down Expand Up @@ -389,7 +389,7 @@ def __download_params_via_mavlink(self, progress_callback=None) -> Dict[str, flo
break
return parameters

def download_params_via_mavftp(self, progress_callback=None) -> Tuple[Dict[str, float], Dict[str, "Par"]]:
def download_params_via_mavftp(self, progress_callback=None) -> tuple[dict[str, float], dict[str, "Par"]]:
if self.master is None:
return {}, {}
mavftp = MAVFTP(self.master, target_system=self.master.target_system, target_component=self.master.target_component)
Expand Down
Loading

0 comments on commit bd7e071

Please sign in to comment.