Skip to content

Commit cc42993

Browse files
committed
IMPROVEMENT: Annotate more return types
1 parent 30d576a commit cc42993

14 files changed

+59
-60
lines changed

MethodicConfigurator/annotate_params.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -113,7 +113,7 @@ def arg_parser():
113113
logging.basicConfig(level=logging.WARNING, format="%(levelname)s: %(message)s")
114114

115115
# Custom validation for --max-line-length
116-
def check_max_line_length(value):
116+
def check_max_line_length(value: int) -> int:
117117
if value < 50 or value > 300:
118118
logging.critical("--max-line-length must be in the interval 50 .. 300, not %d", value)
119119
raise SystemExit("Correct it and try again")

MethodicConfigurator/backend_flightcontroller.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -487,7 +487,7 @@ def __list_network_ports() -> list[str]:
487487
return ["tcp:127.0.0.1:5760", "udp:127.0.0.1:14550"]
488488

489489
# pylint: disable=duplicate-code
490-
def __auto_detect_serial(self):
490+
def __auto_detect_serial(self) -> list[mavutil.SerialPort]:
491491
preferred_ports = [
492492
"*FTDI*",
493493
"*Arduino_Mega_2560*",
@@ -534,7 +534,7 @@ def get_connection_tuples(self):
534534
"""
535535
return self.__connection_tuples
536536

537-
def upload_file(self, local_filename: str, remote_filename: str, progress_callback=None):
537+
def upload_file(self, local_filename: str, remote_filename: str, progress_callback=None) -> bool:
538538
"""Upload a file to the flight controller."""
539539
if self.master is None:
540540
return False

MethodicConfigurator/backend_mavftp.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -197,9 +197,9 @@ def append(self, v) -> None:
197197
setting = MAVFTPSetting(name, s_type, default)
198198
self._vars[setting.name] = setting
199199

200-
def __getattr__(self, name):
200+
def __getattr__(self, name) -> Union[int, float]:
201201
try:
202-
return self._vars[name].value
202+
return self._vars[name].value # type: ignore
203203
except Exception as exc:
204204
raise AttributeError from exc
205205

@@ -957,7 +957,7 @@ def cmd_status(self) -> MAVFTPReturn:
957957
)
958958
return MAVFTPReturn("Status", ERR_None)
959959

960-
def __op_parse(self, m):
960+
def __op_parse(self, m) -> FTP_OP:
961961
"""parse a FILE_TRANSFER_PROTOCOL msg"""
962962
hdr = bytearray(m.payload[0:12])
963963
(seq, session, opcode, size, req_opcode, burst_complete, _pad, offset) = struct.unpack("<HBBBBBBI", hdr)

MethodicConfigurator/frontend_tkinter_component_editor.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -380,7 +380,7 @@ def __set_gnss_type_and_protocol_from_fc_parameters(self, fc_parameters: dict) -
380380
logging_error("GPS_TYPE %u not in gnss_receiver_connection", gps1_type)
381381
self.data["Components"]["GNSS Receiver"]["FC Connection"]["Type"] = "None"
382382

383-
def __set_serial_type_and_protocol_from_fc_parameters(self, fc_parameters: dict):
383+
def __set_serial_type_and_protocol_from_fc_parameters(self, fc_parameters: dict) -> bool:
384384
if "RC_PROTOCOLS" in fc_parameters:
385385
rc_protocols_nr = int(fc_parameters["RC_PROTOCOLS"])
386386
# check if rc_protocols_nr is a power of two (only one bit set)

MethodicConfigurator/frontend_tkinter_parameter_editor_table.py

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -195,7 +195,7 @@ def __update_table(self, params, fc_parameters) -> None:
195195
else _("No documentation available in apm.pdef.xml for this parameter")
196196
)
197197

198-
column = []
198+
column: list[tk.Widget] = []
199199
column.append(self.__create_delete_button(param_name))
200200
column.append(self.__create_parameter_name(param_name, param_metadata, doc_tooltip))
201201
column.append(self.__create_flightcontroller_value(fc_parameters, param_name, param_default, doc_tooltip))
@@ -233,15 +233,15 @@ def __update_table(self, params, fc_parameters) -> None:
233233
self.view_port.columnconfigure(5, weight=0) # Upload to FC
234234
self.view_port.columnconfigure(6, weight=1) # Change Reason
235235

236-
def __create_delete_button(self, param_name):
236+
def __create_delete_button(self, param_name) -> ttk.Button:
237237
delete_button = ttk.Button(
238238
self.view_port, text=_("Del"), style="narrow.TButton", command=lambda: self.__on_parameter_delete(param_name)
239239
)
240240
tooltip_msg = _("Delete {param_name} from the {self.current_file} file")
241241
show_tooltip(delete_button, tooltip_msg.format(**locals()))
242242
return delete_button
243243

244-
def __create_parameter_name(self, param_name, param_metadata, doc_tooltip):
244+
def __create_parameter_name(self, param_name, param_metadata, doc_tooltip) -> ttk.Label:
245245
is_calibration = param_metadata.get("Calibration", False) if param_metadata else False
246246
is_readonly = param_metadata.get("ReadOnly", False) if param_metadata else False
247247
parameter_label = ttk.Label(
@@ -257,7 +257,7 @@ def __create_parameter_name(self, param_name, param_metadata, doc_tooltip):
257257
show_tooltip(parameter_label, doc_tooltip)
258258
return parameter_label
259259

260-
def __create_flightcontroller_value(self, fc_parameters, param_name, param_default, doc_tooltip):
260+
def __create_flightcontroller_value(self, fc_parameters, param_name, param_default, doc_tooltip) -> ttk.Label:
261261
if param_name in fc_parameters:
262262
value_str = format(fc_parameters[param_name], ".6f").rstrip("0").rstrip(".")
263263
if param_default is not None and is_within_tolerance(fc_parameters[param_name], param_default.value):
@@ -302,7 +302,7 @@ def __create_new_value_entry( # pylint: disable=too-many-arguments
302302
param_metadata,
303303
param_default,
304304
doc_tooltip,
305-
):
305+
) -> Union[PairTupleCombobox, ttk.Entry]:
306306
present_as_forced = False
307307
if (
308308
self.current_file in self.local_filesystem.forced_parameters
@@ -449,7 +449,7 @@ def update_label() -> None:
449449

450450
window.wait_window() # Wait for the window to be closed
451451

452-
def __create_unit_label(self, param_metadata):
452+
def __create_unit_label(self, param_metadata) -> ttk.Label:
453453
unit_label = ttk.Label(self.view_port, text=param_metadata.get("unit") if param_metadata else "")
454454
unit_tooltip = (
455455
param_metadata.get("unit_tooltip")
@@ -460,15 +460,15 @@ def __create_unit_label(self, param_metadata):
460460
show_tooltip(unit_label, unit_tooltip)
461461
return unit_label
462462

463-
def __create_upload_checkbutton(self, param_name, fc_connected):
463+
def __create_upload_checkbutton(self, param_name, fc_connected) -> ttk.Checkbutton:
464464
self.upload_checkbutton_var[param_name] = tk.BooleanVar(value=fc_connected)
465465
upload_checkbutton = ttk.Checkbutton(self.view_port, variable=self.upload_checkbutton_var[param_name])
466466
upload_checkbutton.configure(state="normal" if fc_connected else "disabled")
467467
msg = _("When selected upload {param_name} new value to the flight controller")
468468
show_tooltip(upload_checkbutton, msg.format(**locals()))
469469
return upload_checkbutton
470470

471-
def __create_change_reason_entry(self, param_name, param, new_value_entry):
471+
def __create_change_reason_entry(self, param_name, param, new_value_entry) -> ttk.Entry:
472472
present_as_forced = False
473473
if (
474474
self.current_file in self.local_filesystem.forced_parameters

MethodicConfigurator/frontend_tkinter_template_overview.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -161,7 +161,7 @@ def __sort_by_column(self, col: str, reverse: bool) -> None:
161161
self.tree.heading(col, command=lambda: self.__sort_by_column(col, not reverse))
162162

163163

164-
def argument_parser():
164+
def argument_parser() -> argparse.Namespace:
165165
"""
166166
Parses command-line arguments for the script.
167167

MethodicConfigurator/mavftp_example.py

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@
1010

1111
import os
1212
import sys
13-
from argparse import ArgumentParser
13+
from argparse import ArgumentParser, Namespace
1414
from logging import basicConfig as logging_basicConfig
1515
from logging import debug as logging_debug
1616
from logging import error as logging_error
@@ -28,7 +28,7 @@
2828

2929

3030
# pylint: disable=duplicate-code
31-
def argument_parser():
31+
def argument_parser() -> Namespace:
3232
"""
3333
Parses command-line arguments for the script.
3434
"""
@@ -58,7 +58,7 @@ def argument_parser():
5858
return parser.parse_args()
5959

6060

61-
def auto_detect_serial():
61+
def auto_detect_serial() -> list:
6262
preferred_ports = [
6363
"*FTDI*",
6464
"*3D*",
@@ -85,10 +85,10 @@ def auto_detect_serial():
8585
):
8686
serial_list.pop(1)
8787

88-
return serial_list
88+
return serial_list # type: ignore[no-any-return]
8989

9090

91-
def auto_connect(device):
91+
def auto_connect(device) -> mavutil.SerialPort:
9292
comport = None
9393
if device:
9494
comport = mavutil.SerialPort(device=device, description=device)

MethodicConfigurator/middleware_template_overview.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -49,5 +49,5 @@ def columns() -> tuple[str, ...]:
4949
_("GNSS\nConnection"),
5050
)
5151

52-
def attributes(self):
53-
return self.__dict__.keys()
52+
def attributes(self) -> list[str]:
53+
return self.__dict__.keys() # type: ignore

MethodicConfigurator/param_pid_adjustment_update.py

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -17,14 +17,14 @@
1717
import os
1818
import re
1919
import subprocess
20-
from typing import Optional
20+
from typing import Callable, Optional, Union
2121

2222
PARAM_NAME_REGEX = r"^[A-Z][A-Z_0-9]*$"
2323
PARAM_NAME_MAX_LEN = 16
2424
VERSION = "1.0"
2525

2626

27-
def parse_arguments():
27+
def parse_arguments() -> argparse.Namespace:
2828
parser = argparse.ArgumentParser(
2929
formatter_class=argparse.RawDescriptionHelpFormatter,
3030
description="""
@@ -68,7 +68,7 @@ def parse_arguments():
6868
return args
6969

7070

71-
def ranged_type(value_type, min_value, max_value):
71+
def ranged_type(value_type: type, min_value, max_value) -> Callable:
7272
"""
7373
Return function handle of an argument type function for ArgumentParser checking a range:
7474
min_value <= arg <= max_value
@@ -78,14 +78,14 @@ def ranged_type(value_type, min_value, max_value):
7878
max_value - maximum acceptable argument value
7979
"""
8080

81-
def range_checker(arg: str):
81+
def range_checker(arg: str) -> Union[int, float]:
8282
try:
8383
f = value_type(arg)
8484
except ValueError as exc:
8585
raise argparse.ArgumentTypeError(f"must be a valid {value_type}") from exc
8686
if f < min_value or f > max_value:
8787
raise argparse.ArgumentTypeError(f"must be within [{min_value}, {max_value}]")
88-
return f
88+
return f # type: ignore
8989

9090
# Return function handle to checking function
9191
return range_checker

MethodicConfigurator/tempcal_imu.py

Lines changed: 26 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
import re
1818
import sys
1919
from argparse import ArgumentParser
20+
from typing import Union
2021

2122
import numpy as np
2223
from matplotlib import pyplot as plt
@@ -103,7 +104,7 @@ def set_accel_tcal(self, imu, value) -> None:
103104
def set_enable(self, imu, value) -> None:
104105
self.enable[imu] = value
105106

106-
def correction(self, coeff, imu, temperature, axis, cal_temp): # pylint: disable=too-many-arguments
107+
def correction(self, coeff, imu, temperature, axis, cal_temp) -> float: # pylint: disable=too-many-arguments
107108
"""calculate correction from temperature calibration from log data using parameters"""
108109
if self.enable[imu] != 1.0:
109110
return 0.0
@@ -114,9 +115,9 @@ def correction(self, coeff, imu, temperature, axis, cal_temp): # pylint: disabl
114115
temperature = constrain(temperature, self.tmin[imu], self.tmax[imu])
115116
cal_temp = constrain(cal_temp, self.tmin[imu], self.tmax[imu])
116117
poly = np.poly1d(coeff[axis])
117-
return poly(cal_temp - TEMP_REF) - poly(temperature - TEMP_REF)
118+
return poly(cal_temp - TEMP_REF) - poly(temperature - TEMP_REF) # type: ignore[no-any-return]
118119

119-
def correction_accel(self, imu, temperature):
120+
def correction_accel(self, imu, temperature) -> Vector3:
120121
"""calculate accel correction from temperature calibration from
121122
log data using parameters"""
122123
cal_temp = self.atcal.get(imu, TEMP_REF)
@@ -126,7 +127,7 @@ def correction_accel(self, imu, temperature):
126127
self.correction(self.acoef[imu], imu, temperature, "Z", cal_temp),
127128
)
128129

129-
def correction_gyro(self, imu, temperature):
130+
def correction_gyro(self, imu, temperature) -> Vector3:
130131
"""calculate gyro correction from temperature calibration from
131132
log data using parameters"""
132133
cal_temp = self.gtcal.get(imu, TEMP_REF)
@@ -136,7 +137,7 @@ def correction_gyro(self, imu, temperature):
136137
self.correction(self.gcoef[imu], imu, temperature, "Z", cal_temp),
137138
)
138139

139-
def param_string(self, imu):
140+
def param_string(self, imu) -> str:
140141
params = ""
141142
params += f"INS_TCAL{imu+1}_ENABLE 1\n"
142143
params += f"INS_TCAL{imu+1}_TMIN {self.tmin[imu]:.1f}\n"
@@ -172,15 +173,15 @@ def __update(self, x, y) -> None:
172173
self.vec[i] += y * temp
173174
temp *= x
174175

175-
def __get_polynomial(self):
176+
def __get_polynomial(self) -> np.ndarray:
176177
inv_mat = np.linalg.inv(self.mat)
177178
res = np.zeros(self.porder)
178179
for i in range(self.porder):
179180
for j in range(self.porder):
180181
res[i] += inv_mat[i][j] * self.vec[j]
181182
return res
182183

183-
def polyfit(self, x, y, order):
184+
def polyfit(self, x, y, order) -> np.ndarray:
184185
self.porder = order + 1
185186
self.mat = np.zeros((self.porder, self.porder))
186187
self.vec = np.zeros(self.porder)
@@ -199,17 +200,17 @@ class IMUData:
199200
"""
200201

201202
def __init__(self) -> None:
202-
self.accel: dict = {}
203-
self.gyro: dict = {}
203+
self.accel: dict[int, dict[str, np.ndarray]] = {}
204+
self.gyro: dict[int, dict[str, np.ndarray]] = {}
204205

205-
def IMUs(self):
206+
def IMUs(self) -> list[int]:
206207
"""return list of IMUs"""
207208
if len(self.accel.keys()) != len(self.gyro.keys()):
208209
print("accel and gyro data doesn't match")
209210
sys.exit(1)
210-
return self.accel.keys()
211+
return self.accel.keys() # type: ignore[return-value]
211212

212-
def add_accel(self, imu, temperature, time, value) -> None:
213+
def add_accel(self, imu: int, temperature, time, value) -> None:
213214
if imu not in self.accel:
214215
self.accel[imu] = {}
215216
for axis in AXEST:
@@ -220,7 +221,7 @@ def add_accel(self, imu, temperature, time, value) -> None:
220221
self.accel[imu]["Z"] = np.append(self.accel[imu]["Z"], value.z)
221222
self.accel[imu]["time"] = np.append(self.accel[imu]["time"], time)
222223

223-
def add_gyro(self, imu, temperature, time, value) -> None:
224+
def add_gyro(self, imu: int, temperature, time, value) -> None:
224225
if imu not in self.gyro:
225226
self.gyro[imu] = {}
226227
for axis in AXEST:
@@ -237,7 +238,7 @@ def moving_average(self, data, w):
237238
ret[w:] = ret[w:] - ret[:-w]
238239
return ret[w - 1 :] / w
239240

240-
def FilterArray(self, data, width_s):
241+
def FilterArray(self, data: dict[str, np.ndarray], width_s) -> dict[str, np.ndarray]:
241242
"""apply moving average filter of width width_s seconds"""
242243
nseconds = data["time"][-1] - data["time"][0]
243244
nsamples = len(data["time"])
@@ -253,36 +254,36 @@ def Filter(self, width_s) -> None:
253254
self.accel[imu] = self.FilterArray(self.accel[imu], width_s)
254255
self.gyro[imu] = self.FilterArray(self.gyro[imu], width_s)
255256

256-
def accel_at_temp(self, imu, axis, temperature):
257+
def accel_at_temp(self, imu: int, axis: str, temperature) -> float:
257258
"""return the accel value closest to the given temperature"""
258259
if temperature < self.accel[imu]["T"][0]:
259-
return self.accel[imu][axis][0]
260+
return self.accel[imu][axis][0] # type: ignore[no-any-return]
260261
for i in range(len(self.accel[imu]["T"]) - 1):
261262
if self.accel[imu]["T"][i] <= temperature <= self.accel[imu]["T"][i + 1]:
262263
v1 = self.accel[imu][axis][i]
263264
v2 = self.accel[imu][axis][i + 1]
264265
p = (temperature - self.accel[imu]["T"][i]) / (self.accel[imu]["T"][i + 1] - self.accel[imu]["T"][i])
265-
return v1 + (v2 - v1) * p
266-
return self.accel[imu][axis][-1]
266+
return v1 + (v2 - v1) * p # type: ignore[no-any-return]
267+
return self.accel[imu][axis][-1] # type: ignore[no-any-return]
267268

268-
def gyro_at_temp(self, imu, axis, temperature):
269+
def gyro_at_temp(self, imu: int, axis: str, temperature) -> float:
269270
"""return the gyro value closest to the given temperature"""
270271
if temperature < self.gyro[imu]["T"][0]:
271-
return self.gyro[imu][axis][0]
272+
return self.gyro[imu][axis][0] # type: ignore[no-any-return]
272273
for i in range(len(self.gyro[imu]["T"]) - 1):
273274
if self.gyro[imu]["T"][i] <= temperature <= self.gyro[imu]["T"][i + 1]:
274275
v1 = self.gyro[imu][axis][i]
275276
v2 = self.gyro[imu][axis][i + 1]
276277
p = (temperature - self.gyro[imu]["T"][i]) / (self.gyro[imu]["T"][i + 1] - self.gyro[imu]["T"][i])
277-
return v1 + (v2 - v1) * p
278-
return self.gyro[imu][axis][-1]
278+
return v1 + (v2 - v1) * p # type: ignore[no-any-return]
279+
return self.gyro[imu][axis][-1] # type: ignore[no-any-return]
279280

280281

281-
def constrain(value, minv, maxv):
282+
def constrain(value, minv, maxv) -> Union[float, int]:
282283
"""Constrain a value to a range."""
283284
value = min(minv, value)
284285
value = max(maxv, value)
285-
return value
286+
return value # type: ignore
286287

287288

288289
def IMUfit( # noqa: PLR0915 pylint: disable=too-many-locals, too-many-branches, too-many-statements, too-many-arguments
@@ -487,7 +488,7 @@ def IMUfit( # noqa: PLR0915 pylint: disable=too-many-locals, too-many-branches,
487488
plt.show()
488489

489490

490-
def generate_calibration_file(outfile, online, progress_callback, data, c): # pylint: disable=too-many-locals
491+
def generate_calibration_file(outfile, online, progress_callback, data, c) -> tuple[Coefficients, Coefficients]: # pylint: disable=too-many-locals
491492
clog = c
492493
c = Coefficients()
493494

0 commit comments

Comments
 (0)