Skip to content

Commit c603a92

Browse files
committed
IMPROVEMENT: Add more return type hints
1 parent d606483 commit c603a92

22 files changed

+64
-64
lines changed

MethodicConfigurator/annotate_params.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@
5050
# mypy: disable-error-code="unused-ignore"
5151

5252

53-
def arg_parser():
53+
def arg_parser() -> argparse.Namespace:
5454
parser = argparse.ArgumentParser(
5555
description="Fetches on-line ArduPilot parameter documentation and adds it to the "
5656
"specified file or to all *.param and *.parm files in the specified directory."

MethodicConfigurator/ardupilot_methodic_configurator.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@
3030
from MethodicConfigurator.frontend_tkinter_parameter_editor import ParameterEditorWindow
3131

3232

33-
def argument_parser():
33+
def argument_parser() -> argparse.Namespace:
3434
"""
3535
Parses command-line arguments for the script.
3636

MethodicConfigurator/argparse_check_range.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ def __init__(self, *args, **kwargs) -> None:
3434

3535
super().__init__(*args, **kwargs)
3636

37-
def interval(self):
37+
def interval(self) -> str:
3838
if hasattr(self, "min"):
3939
_lo = f"[{self.min}"
4040
elif hasattr(self, "inf"):

MethodicConfigurator/backend_filesystem.py

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -382,11 +382,11 @@ def get_directory_name_from_full_path(full_path: str) -> str:
382382
def get_vehicle_directory_name(self) -> str:
383383
return self.get_directory_name_from_full_path(self.vehicle_dir)
384384

385-
def zip_file_path(self):
385+
def zip_file_path(self) -> str:
386386
vehicle_name = self.get_vehicle_directory_name()
387387
return os_path.join(self.vehicle_dir, f"{vehicle_name}.zip")
388388

389-
def zip_file_exists(self):
389+
def zip_file_exists(self) -> bool:
390390
zip_file_path = self.zip_file_path()
391391
return os_path.exists(zip_file_path) and os_path.isfile(zip_file_path)
392392

@@ -436,10 +436,10 @@ def zip_files(self, files_to_zip: list[tuple[bool, str]]) -> None:
436436

437437
logging_info(_("Intermediate parameter files and summary files zipped to %s"), zip_file_path)
438438

439-
def vehicle_image_filepath(self):
439+
def vehicle_image_filepath(self) -> str:
440440
return os_path.join(self.vehicle_dir, "vehicle.jpg")
441441

442-
def vehicle_image_exists(self):
442+
def vehicle_image_exists(self) -> bool:
443443
return os_path.exists(self.vehicle_image_filepath()) and os_path.isfile(self.vehicle_image_filepath())
444444

445445
@staticmethod
@@ -477,11 +477,11 @@ def copy_template_files_to_new_vehicle_dir(self, template_dir: str, new_vehicle_
477477
def getcwd() -> str:
478478
return os_getcwd()
479479

480-
def tempcal_imu_result_param_tuple(self):
480+
def tempcal_imu_result_param_tuple(self) -> tuple[str, str]:
481481
tempcal_imu_result_param_filename = "03_imu_temperature_calibration_results.param"
482-
return [tempcal_imu_result_param_filename, os_path.join(self.vehicle_dir, tempcal_imu_result_param_filename)]
482+
return tempcal_imu_result_param_filename, os_path.join(self.vehicle_dir, tempcal_imu_result_param_filename)
483483

484-
def copy_fc_values_to_file(self, selected_file: str, params: dict[str, float]):
484+
def copy_fc_values_to_file(self, selected_file: str, params: dict[str, float]) -> int:
485485
ret = 0
486486
if selected_file in self.file_parameters:
487487
for param, v in self.file_parameters[selected_file].items():
@@ -557,15 +557,15 @@ def get_start_file(self, explicit_index: int, tcal_available: bool) -> str:
557557
start_file_index = len(files) - 1
558558
return files[start_file_index]
559559

560-
def get_eval_variables(self):
560+
def get_eval_variables(self) -> dict[str, dict[str, Any]]:
561561
variables = {}
562562
if hasattr(self, "vehicle_components") and self.vehicle_components and "Components" in self.vehicle_components:
563563
variables["vehicle_components"] = self.vehicle_components["Components"]
564564
if hasattr(self, "doc_dict") and self.doc_dict:
565565
variables["doc_dict"] = self.doc_dict
566566
return variables
567567

568-
def copy_fc_params_values_to_template_created_vehicle_files(self, fc_parameters: dict[str, float]):
568+
def copy_fc_params_values_to_template_created_vehicle_files(self, fc_parameters: dict[str, float]) -> str:
569569
eval_variables = self.get_eval_variables()
570570
for param_filename, param_dict in self.file_parameters.items():
571571
for param_name, param in param_dict.items():

MethodicConfigurator/backend_filesystem_configuration_steps.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -176,9 +176,9 @@ def compute_parameters(self, filename: str, file_info: dict, parameter_type: str
176176
logging_warning(error_msg)
177177
return ""
178178

179-
def auto_changed_by(self, selected_file: str):
179+
def auto_changed_by(self, selected_file: str) -> str:
180180
if selected_file in self.configuration_steps:
181-
return self.configuration_steps[selected_file].get("auto_changed_by", "")
181+
return str(self.configuration_steps[selected_file].get("auto_changed_by", ""))
182182
return ""
183183

184184
def jump_possible(self, selected_file: str) -> dict[str, str]:

MethodicConfigurator/backend_filesystem_vehicle_components.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@ def __init__(self) -> None:
3838
self.vehicle_components_json_filename = "vehicle_components.json"
3939
self.vehicle_components: Union[None, dict[Any, Any]] = None
4040

41-
def load_vehicle_components_json_data(self, vehicle_dir: str):
41+
def load_vehicle_components_json_data(self, vehicle_dir: str) -> dict[Any, Any]:
4242
data = {}
4343
filepath = os_path.join(vehicle_dir, self.vehicle_components_json_filename)
4444
try:

MethodicConfigurator/backend_flightcontroller.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -416,7 +416,7 @@ def get_params_progress_callback(completion: float) -> None:
416416

417417
return pdict, defdict
418418

419-
def set_param(self, param_name: str, param_value: float):
419+
def set_param(self, param_name: str, param_value: float) -> None:
420420
"""
421421
Set a parameter on the flight controller.
422422
@@ -425,8 +425,8 @@ def set_param(self, param_name: str, param_value: float):
425425
param_value (float): The value to set the parameter to.
426426
"""
427427
if self.master is None: # FIXME for testing only pylint: disable=fixme
428-
return None
429-
return self.master.param_set_send(param_name, param_value)
428+
return
429+
self.master.param_set_send(param_name, param_value)
430430

431431
def reset_and_reconnect(
432432
self, reset_progress_callback=None, connection_progress_callback=None, extra_sleep_time: Optional[int] = None
@@ -528,7 +528,7 @@ def __auto_detect_serial(self) -> list[mavutil.SerialPort]:
528528

529529
# pylint: enable=duplicate-code
530530

531-
def get_connection_tuples(self):
531+
def get_connection_tuples(self) -> list[tuple[str, str]]:
532532
"""
533533
Get all available connections.
534534
"""

MethodicConfigurator/backend_flightcontroller_info.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@
88
SPDX-License-Identifier: GPL-3.0-or-later
99
"""
1010

11-
from typing import Any
11+
from typing import Any, Union
1212

1313
from pymavlink import mavutil
1414

@@ -45,7 +45,7 @@ def __init__(self) -> None:
4545
self.is_supported = False
4646
self.is_mavftp_supported = False
4747

48-
def get_info(self):
48+
def get_info(self) -> dict[str, Union[str, dict[str, str]]]:
4949
return {
5050
"Vendor": self.vendor_and_vendor_id,
5151
"Product": self.product_and_product_id,

MethodicConfigurator/backend_mavftp.py

Lines changed: 9 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,8 @@
1717
import struct
1818
import sys
1919
import time
20-
from argparse import ArgumentParser
20+
from argparse import ArgumentParser, Namespace
21+
from collections.abc import Generator
2122
from datetime import datetime
2223
from io import BufferedReader, BufferedWriter
2324
from io import BytesIO as SIO
@@ -106,7 +107,7 @@ def __init__( # pylint: disable=too-many-arguments, too-many-positional-argumen
106107
self.offset: int = offset # Offset for read/write operations.
107108
self.payload = payload # (bytes) Payload for the operation.
108109

109-
def pack(self):
110+
def pack(self) -> bytearray:
110111
"""pack message"""
111112
ret = struct.pack(
112113
"<HBBBBBBI", self.seq, self.session, self.opcode, self.size, self.req_opcode, self.burst_complete, 0, self.offset
@@ -128,7 +129,7 @@ def __str__(self) -> str:
128129
ret += f" [{self.payload[0]}]"
129130
return ret
130131

131-
def items(self):
132+
def items(self) -> Generator[tuple[str, Union[int, bool, bytes]]]:
132133
"""Yield each attribute and its value for the FTP_OP instance. For debugging purposes."""
133134
yield "seq", self.seq
134135
yield "session", self.session
@@ -280,7 +281,7 @@ def display_message(self) -> None: # pylint: disable=too-many-branches
280281
logging.error("%s failed, unknown error %u in display_message()", self.operation_name, self.error_code)
281282

282283
@property
283-
def return_code(self):
284+
def return_code(self) -> int:
284285
return self.error_code
285286

286287

@@ -1397,7 +1398,7 @@ def decode_and_save_params(fh) -> MAVFTPReturn:
13971398

13981399
if __name__ == "__main__":
13991400

1400-
def argument_parser():
1401+
def argument_parser() -> Namespace:
14011402
"""
14021403
Parses command-line arguments for the script.
14031404
@@ -1529,7 +1530,7 @@ def argument_parser():
15291530
# Add other subparsers commands as needed
15301531
return parser.parse_args()
15311532

1532-
def auto_detect_serial():
1533+
def auto_detect_serial() -> list[mavutil.SerialPort]:
15331534
preferred_ports = [
15341535
"*FTDI*",
15351536
"*3D*",
@@ -1545,7 +1546,7 @@ def auto_detect_serial():
15451546
"*CubePilot*",
15461547
"*Qiotek*",
15471548
]
1548-
serial_list = mavutil.auto_detect_serial(preferred_list=preferred_ports)
1549+
serial_list: list[mavutil.SerialPort] = mavutil.auto_detect_serial(preferred_list=preferred_ports)
15491550
serial_list.sort(key=lambda x: x.device)
15501551

15511552
# remove OTG2 ports for dual CDC
@@ -1558,7 +1559,7 @@ def auto_detect_serial():
15581559

15591560
return serial_list
15601561

1561-
def auto_connect(device):
1562+
def auto_connect(device) -> mavutil.SerialPort:
15621563
comport = None
15631564
if device:
15641565
comport = mavutil.SerialPort(device=device, description=device)

MethodicConfigurator/extract_param_defaults.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@
2727
MAV_PARAM_TYPE_REAL32 = 9
2828

2929

30-
def parse_arguments(args=None):
30+
def parse_arguments(args=None) -> argparse.Namespace:
3131
"""
3232
Parses command line arguments for the script.
3333
@@ -92,7 +92,7 @@ def parse_arguments(args=None):
9292
if args.compid != -1:
9393
raise SystemExit("--compid parameter is only relevant if --format is qgcs")
9494

95-
return args
95+
return args # type: ignore # mypy bug
9696

9797

9898
def extract_parameter_values(logfile: str, param_type: str = "defaults") -> dict[str, float]: # pylint: disable=too-many-branches

0 commit comments

Comments
 (0)