Skip to content

Commit a140716

Browse files
committed
IMPROVEMENT: Drop support for python 3.8
Python 3.8 has very limited support for type hints. Type hints make the code more readable and less error prone
1 parent 0e0cbc4 commit a140716

16 files changed

+72
-80
lines changed

.github/workflows/pylint.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ jobs:
77
runs-on: ubuntu-latest
88
strategy:
99
matrix:
10-
python-version: ["3.8", "3.11"]
10+
python-version: ["3.9", "3.11"]
1111
steps:
1212

1313
- name: Checkout

MethodicConfigurator/annotate_params.py

Lines changed: 18 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@
3131
from sys import exc_info as sys_exc_info
3232
from sys import exit as sys_exit
3333
from types import TracebackType
34-
from typing import Any, Dict, List, Optional, Tuple
34+
from typing import Any, Optional
3535
from xml.etree import ElementTree as ET # no parsing, just data-structure manipulation
3636

3737
from defusedxml import ElementTree as DET # just parsing, no data-structure manipulation
@@ -141,7 +141,7 @@ def __eq__(self, other: object) -> bool:
141141
return False
142142

143143
@staticmethod
144-
def load_param_file_into_dict(param_file: str) -> Dict[str, "Par"]:
144+
def load_param_file_into_dict(param_file: str) -> dict[str, "Par"]:
145145
"""
146146
Loads an ArduPilot parameter file into a dictionary with name, value pairs.
147147
@@ -151,7 +151,7 @@ def load_param_file_into_dict(param_file: str) -> Dict[str, "Par"]:
151151
Returns:
152152
dict: A dictionary containing the parameters from the file.
153153
"""
154-
parameter_dict: Dict[str, Par] = {}
154+
parameter_dict: dict[str, Par] = {}
155155
try:
156156
with open(param_file, encoding="utf-8") as f_handle:
157157
for i, f_line in enumerate(f_handle, start=1):
@@ -202,7 +202,7 @@ def validate_parameter(param_file, parameter_dict, i, original_line, comment, pa
202202
raise SystemExit(f"Caused by line {i} of file {param_file}: {original_line}") from exc
203203

204204
@staticmethod
205-
def missionplanner_sort(item: str) -> Tuple[str, ...]:
205+
def missionplanner_sort(item: str) -> tuple[str, ...]:
206206
"""
207207
Sorts a parameter name according to the rules defined in the Mission Planner software.
208208
@@ -217,7 +217,7 @@ def missionplanner_sort(item: str) -> Tuple[str, ...]:
217217
return tuple(parts)
218218

219219
@staticmethod
220-
def format_params(param_dict: Dict[str, "Par"], file_format: str = "missionplanner") -> List[str]: # pylint: disable=too-many-branches
220+
def format_params(param_dict: dict[str, "Par"], file_format: str = "missionplanner") -> list[str]: # pylint: disable=too-many-branches
221221
"""
222222
Formats the parameters in the provided dictionary into a list of strings.
223223
@@ -266,7 +266,7 @@ def format_params(param_dict: Dict[str, "Par"], file_format: str = "missionplann
266266
return formatted_params
267267

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

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

391391

392-
def load_default_param_file(directory: str) -> Dict[str, "Par"]:
393-
param_default_dict: Dict[str, Par] = {}
392+
def load_default_param_file(directory: str) -> dict[str, "Par"]:
393+
param_default_dict: dict[str, Par] = {}
394394
# Load parameter default values if the 00_default.param file exists
395395
try:
396396
param_default_dict = Par.load_param_file_into_dict(os_path.join(directory, "00_default.param"))
@@ -416,7 +416,7 @@ def remove_prefix(text: str, prefix: str) -> str:
416416
return text
417417

418418

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

434434

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

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

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

490490

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

547547

548-
def missionplanner_sort(item: str) -> Tuple[str, ...]:
548+
def missionplanner_sort(item: str) -> tuple[str, ...]:
549549
"""
550550
MissionPlanner parameter sorting function
551551
"""
@@ -584,10 +584,10 @@ def extract_parameter_name_and_validate(line: str, filename: str, line_nr: int)
584584

585585

586586
def update_parameter_documentation(
587-
doc: Dict[str, Any],
587+
doc: dict[str, Any],
588588
target: str = ".",
589589
sort_type: str = "none",
590-
param_default_dict: Optional[Dict] = None,
590+
param_default_dict: Optional[dict] = None,
591591
delete_documentation_annotations=False,
592592
) -> None:
593593
"""
@@ -742,7 +742,7 @@ def get_xml_url(vehicle_type: str, firmware_version: str) -> str:
742742

743743
def parse_parameter_metadata(
744744
xml_url: str, xml_dir: str, xml_file: str, vehicle_type: str, max_line_length: int
745-
) -> Dict[str, Any]:
745+
) -> dict[str, Any]:
746746
xml_root = get_xml_data(xml_url, xml_dir, xml_file, vehicle_type)
747747
return create_doc_dict(xml_root, vehicle_type, max_line_length)
748748

MethodicConfigurator/ardupilot_methodic_configurator.py

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,6 @@
1717
from logging import getLevelName as logging_getLevelName
1818
from logging import info as logging_info
1919
from sys import exit as sys_exit
20-
from typing import Tuple
2120

2221
from MethodicConfigurator import _, __version__
2322
from MethodicConfigurator.backend_filesystem import LocalFilesystem
@@ -61,7 +60,7 @@ def argument_parser():
6160
return add_common_arguments_and_parse(parser)
6261

6362

64-
def connect_to_fc_and_read_parameters(args) -> Tuple[FlightController, str]:
63+
def connect_to_fc_and_read_parameters(args) -> tuple[FlightController, str]:
6564
flight_controller = FlightController(args.reboot_time)
6665

6766
error_str = flight_controller.connect(args.device, log_errors=False)

MethodicConfigurator/backend_filesystem.py

Lines changed: 17 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121
from re import compile as re_compile
2222
from shutil import copy2 as shutil_copy2
2323
from shutil import copytree as shutil_copytree
24-
from typing import Any, Dict, List, Tuple
24+
from typing import Any
2525
from zipfile import ZipFile
2626

2727
from requests import get as requests_get
@@ -82,16 +82,16 @@ class LocalFilesystem(VehicleComponents, ConfigurationSteps, ProgramSettings):
8282
"""
8383

8484
def __init__(self, vehicle_dir: str, vehicle_type: str, fw_version: str, allow_editing_template_files: bool):
85-
self.file_parameters: Dict[str, Dict[str, Par]] = {}
85+
self.file_parameters: dict[str, dict[str, Par]] = {}
8686
VehicleComponents.__init__(self)
8787
ConfigurationSteps.__init__(self, vehicle_dir, vehicle_type)
8888
ProgramSettings.__init__(self)
8989
self.vehicle_type = vehicle_type
9090
self.fw_version = fw_version
9191
self.allow_editing_template_files = allow_editing_template_files
92-
self.param_default_dict: Dict[str, Par] = {}
92+
self.param_default_dict: dict[str, Par] = {}
9393
self.vehicle_dir = vehicle_dir
94-
self.doc_dict: Dict[str, Any] = {}
94+
self.doc_dict: dict[str, Any] = {}
9595
if vehicle_dir is not None:
9696
self.re_init(vehicle_dir, vehicle_type)
9797

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

218-
def read_params_from_files(self) -> Dict[str, Dict[str, "Par"]]:
218+
def read_params_from_files(self) -> dict[str, dict[str, "Par"]]:
219219
"""
220220
Reads intermediate parameter files from a directory and stores their contents in a dictionary.
221221
@@ -227,7 +227,7 @@ def read_params_from_files(self) -> Dict[str, Dict[str, "Par"]]:
227227
- Dict[str, Dict[str, 'Par']]: A dictionary with filenames as keys and as values
228228
a dictionary with (parameter names, values) pairs.
229229
"""
230-
parameters: Dict[str, Dict[str, Par]] = {}
230+
parameters: dict[str, dict[str, Par]] = {}
231231
if os_path.isdir(self.vehicle_dir):
232232
# Regular expression pattern for filenames starting with two digits followed by an underscore and ending in .param
233233
pattern = re_compile(r"^\d{2}_.*\.param$")
@@ -261,7 +261,7 @@ def str_to_bool(s):
261261
return False
262262
return None
263263

264-
def export_to_param(self, params: Dict[str, "Par"], filename_out: str, annotate_doc: bool = True) -> None:
264+
def export_to_param(self, params: dict[str, "Par"], filename_out: str, annotate_doc: bool = True) -> None:
265265
"""
266266
Exports a dictionary of parameters to a .param file and optionally annotates the documentation.
267267
@@ -293,7 +293,7 @@ def vehicle_configuration_file_exists(self, filename: str) -> bool:
293293
os_path.join(self.vehicle_dir, filename)
294294
)
295295

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

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

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

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

472-
def copy_fc_values_to_file(self, selected_file: str, params: Dict[str, float]):
472+
def copy_fc_values_to_file(self, selected_file: str, params: dict[str, float]):
473473
ret = 0
474474
if selected_file in self.file_parameters:
475475
for param, v in self.file_parameters[selected_file].items():
@@ -553,7 +553,7 @@ def get_eval_variables(self):
553553
variables["doc_dict"] = self.doc_dict
554554
return variables
555555

556-
def copy_fc_params_values_to_template_created_vehicle_files(self, fc_parameters: Dict[str, float]):
556+
def copy_fc_params_values_to_template_created_vehicle_files(self, fc_parameters: dict[str, float]):
557557
eval_variables = self.get_eval_variables()
558558
for param_filename, param_dict in self.file_parameters.items():
559559
for param_name, param in param_dict.items():
@@ -570,18 +570,18 @@ def copy_fc_params_values_to_template_created_vehicle_files(self, fc_parameters:
570570
Par.export_to_param(Par.format_params(param_dict), os_path.join(self.vehicle_dir, param_filename))
571571
return ""
572572

573-
def write_param_default_values(self, param_default_values: Dict[str, "Par"]) -> bool:
573+
def write_param_default_values(self, param_default_values: dict[str, "Par"]) -> bool:
574574
param_default_values = dict(sorted(param_default_values.items()))
575575
if self.param_default_dict != param_default_values:
576576
self.param_default_dict = param_default_values
577577
return True
578578
return False
579579

580-
def write_param_default_values_to_file(self, param_default_values: Dict[str, "Par"], filename: str = "00_default.param"):
580+
def write_param_default_values_to_file(self, param_default_values: dict[str, "Par"], filename: str = "00_default.param"):
581581
if self.write_param_default_values(param_default_values):
582582
Par.export_to_param(Par.format_params(self.param_default_dict), os_path.join(self.vehicle_dir, filename))
583583

584-
def get_download_url_and_local_filename(self, selected_file: str) -> Tuple[str, str]:
584+
def get_download_url_and_local_filename(self, selected_file: str) -> tuple[str, str]:
585585
if (
586586
selected_file in self.configuration_steps
587587
and "download_file" in self.configuration_steps[selected_file]
@@ -593,7 +593,7 @@ def get_download_url_and_local_filename(self, selected_file: str) -> Tuple[str,
593593
return src, os_path.join(self.vehicle_dir, dst)
594594
return "", ""
595595

596-
def get_upload_local_and_remote_filenames(self, selected_file: str) -> Tuple[str, str]:
596+
def get_upload_local_and_remote_filenames(self, selected_file: str) -> tuple[str, str]:
597597
if (
598598
selected_file in self.configuration_steps
599599
and "upload_file" in self.configuration_steps[selected_file]

MethodicConfigurator/backend_filesystem_configuration_steps.py

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,6 @@
1717
from logging import info as logging_info
1818
from logging import warning as logging_warning
1919
from os import path as os_path
20-
from typing import Tuple
2120

2221
from MethodicConfigurator import _
2322
from MethodicConfigurator.annotate_params import Par
@@ -175,7 +174,7 @@ def jump_possible(self, selected_file: str):
175174
return self.configuration_steps[selected_file].get("jump_possible", {})
176175
return {}
177176

178-
def get_documentation_text_and_url(self, selected_file: str, prefix_key: str) -> Tuple[str, str]:
177+
def get_documentation_text_and_url(self, selected_file: str, prefix_key: str) -> tuple[str, str]:
179178
documentation = self.configuration_steps.get(selected_file, {}) if self.configuration_steps else None
180179
if documentation is None:
181180
text = _(

MethodicConfigurator/backend_flightcontroller.py

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@
1717
from os import readlink as os_readlink
1818
from time import sleep as time_sleep
1919
from time import time as time_time
20-
from typing import Dict, List, Optional, Tuple
20+
from typing import Optional, Union
2121

2222
import serial.tools.list_ports
2323
import serial.tools.list_ports_common
@@ -81,8 +81,8 @@ def __init__(self, reboot_time: int):
8181
self.__reboot_time = reboot_time
8282
self.__connection_tuples: list[tuple[str, str]] = []
8383
self.discover_connections()
84-
self.master: mavutil.mavlink_connection | None = None
85-
self.comport: mavutil.SerialPort | None = None
84+
self.master: Union[mavutil.mavlink_connection, None] = None
85+
self.comport: Union[mavutil.SerialPort, None] = None
8686
self.fc_parameters: dict[str, float] = {}
8787
self.info = BackendFlightcontrollerInfo()
8888

@@ -188,7 +188,7 @@ def __request_banner(self):
188188
0,
189189
)
190190

191-
def __receive_banner_text(self) -> List[str]:
191+
def __receive_banner_text(self) -> list[str]:
192192
"""Starts listening for STATUS_TEXT MAVLink messages."""
193193
start_time = time_time()
194194
banner_msgs: list[str] = []
@@ -324,7 +324,7 @@ def __process_autopilot_version(self, m, banner_msgs) -> str:
324324
self.info.product = fc_product # force the one from the banner because it is more reliable
325325
return ""
326326

327-
def download_params(self, progress_callback=None) -> Tuple[Dict[str, float], Dict[str, "Par"]]:
327+
def download_params(self, progress_callback=None) -> tuple[dict[str, float], dict[str, "Par"]]:
328328
"""
329329
Requests all flight controller parameters from a MAVLink connection.
330330
@@ -352,7 +352,7 @@ def download_params(self, progress_callback=None) -> Tuple[Dict[str, float], Dic
352352
logging_info(_("MAVFTP is not supported by the %s flight controller, fallback to MAVLink"), comport_device)
353353
return self.__download_params_via_mavlink(progress_callback), {}
354354

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

@@ -389,7 +389,7 @@ def __download_params_via_mavlink(self, progress_callback=None) -> Dict[str, flo
389389
break
390390
return parameters
391391

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

0 commit comments

Comments
 (0)