Skip to content

Commit 00df0b3

Browse files
committed
chore(ty): type safety improvements using ty
1 parent 00ab02d commit 00df0b3

32 files changed

+186
-91
lines changed

ardupilot_methodic_configurator/backend_flightcontroller.py

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -289,8 +289,7 @@ def reset_and_reconnect(
289289
logging_warning(_("Cannot reset flight controller: not connected"))
290290
return ""
291291
# Issue a reset
292-
# Type ignore needed because MavlinkConnection is a Union including object fallback
293-
self.master.reboot_autopilot() # type: ignore[union-attr]
292+
self.master.reboot_autopilot()
294293
logging_info(_("Reset command sent to ArduPilot."))
295294
time_sleep(0.3) # Short delay for command to be sent
296295

ardupilot_methodic_configurator/backend_flightcontroller_commands.py

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -122,9 +122,9 @@ def send_command_and_wait_ack( # pylint: disable=too-many-arguments,too-many-po
122122

123123
try:
124124
# Send the command
125-
self.master.mav.command_long_send( # type: ignore[union-attr] # pyright: ignore[reportAttributeAccessIssue]
126-
self.master.target_system, # type: ignore[union-attr] # pyright: ignore[reportAttributeAccessIssue]
127-
self.master.target_component, # type: ignore[union-attr] # pyright: ignore[reportAttributeAccessIssue]
125+
self.master.mav.command_long_send( # pyright: ignore[reportAttributeAccessIssue]
126+
self.master.target_system, # pyright: ignore[reportAttributeAccessIssue]
127+
self.master.target_component, # pyright: ignore[reportAttributeAccessIssue]
128128
command,
129129
0, # confirmation
130130
param1,
@@ -139,7 +139,7 @@ def send_command_and_wait_ack( # pylint: disable=too-many-arguments,too-many-po
139139
# Wait for acknowledgment
140140
start_time = time_time()
141141
while time_time() - start_time < timeout:
142-
msg = self.master.recv_match( # type: ignore[union-attr] # pyright: ignore[reportAttributeAccessIssue]
142+
msg = self.master.recv_match( # pyright: ignore[reportAttributeAccessIssue]
143143
type="COMMAND_ACK", blocking=False
144144
)
145145
if msg and msg.command == command:
@@ -305,9 +305,9 @@ def test_all_motors(self, nr_of_motors: int, throttle_percent: int, timeout_seco
305305

306306
for i in range(nr_of_motors):
307307
# MAV_CMD_DO_MOTOR_TEST command for all motors
308-
self.master.mav.command_long_send( # type: ignore[union-attr] # pyright: ignore[reportAttributeAccessIssue]
309-
self.master.target_system, # type: ignore[union-attr] # pyright: ignore[reportAttributeAccessIssue]
310-
self.master.target_component, # type: ignore[union-attr] # pyright: ignore[reportAttributeAccessIssue]
308+
self.master.mav.command_long_send( # pyright: ignore[reportAttributeAccessIssue]
309+
self.master.target_system, # pyright: ignore[reportAttributeAccessIssue]
310+
self.master.target_component, # pyright: ignore[reportAttributeAccessIssue]
311311
mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST,
312312
0, # confirmation
313313
param1=i + 1, # motor number (1-based)
@@ -482,7 +482,7 @@ def get_battery_status(self) -> tuple[Union[tuple[float, float], None], str]:
482482

483483
try:
484484
# Try to get real telemetry data
485-
battery_status = self.master.recv_match( # type: ignore[union-attr] # pyright: ignore[reportAttributeAccessIssue]
485+
battery_status = self.master.recv_match( # pyright: ignore[reportAttributeAccessIssue]
486486
type="BATTERY_STATUS", blocking=False, timeout=self.BATTERY_STATUS_TIMEOUT
487487
)
488488
if battery_status:

ardupilot_methodic_configurator/backend_flightcontroller_connection.py

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -203,7 +203,7 @@ def disconnect(self) -> None:
203203
"""Close the connection to the flight controller."""
204204
if self.master is not None:
205205
with contextlib.suppress(Exception):
206-
self.master.close() # type: ignore[union-attr] # pyright: ignore[reportAttributeAccessIssue]
206+
self.master.close() # pyright: ignore[reportAttributeAccessIssue]
207207
self.master = None
208208
self.info.reset()
209209

@@ -368,7 +368,7 @@ def _create_mavlink_connection( # pylint: disable=too-many-arguments, too-many-
368368
timeout: int = 5,
369369
retries: int = 3,
370370
progress_callback: Union[None, Callable[[int, int], None]] = None,
371-
) -> mavutil.mavlink_connection: # pyright: ignore[reportGeneralTypeIssues]
371+
) -> Union["MavlinkConnection", None]:
372372
"""
373373
Factory method for creating MAVLink connections.
374374
@@ -410,7 +410,7 @@ def _detect_vehicles_from_heartbeats(self, timeout: int) -> dict[tuple[int, int]
410410
while time_time() - start_time < timeout:
411411
try:
412412
m = (
413-
self.master.recv_match( # type: ignore[union-attr] # pyright: ignore[reportAttributeAccessIssue]
413+
self.master.recv_match( # pyright: ignore[reportAttributeAccessIssue]
414414
type="HEARTBEAT", blocking=False
415415
)
416416
if self.master
@@ -483,7 +483,7 @@ def _retrieve_autopilot_version_and_banner(self, timeout: int) -> str:
483483
# Request AUTOPILOT_VERSION message
484484
self._request_message(mavutil.mavlink.MAVLINK_MSG_ID_AUTOPILOT_VERSION)
485485
m = (
486-
self.master.recv_match( # type: ignore[union-attr] # pyright: ignore[reportAttributeAccessIssue]
486+
self.master.recv_match( # pyright: ignore[reportAttributeAccessIssue]
487487
type="AUTOPILOT_VERSION", blocking=True, timeout=timeout
488488
)
489489
if self.master
@@ -498,9 +498,9 @@ def _request_banner(self) -> None:
498498
if self.master is not None:
499499
# Note: Don't wait for ACK here as banner requests are fire-and-forget
500500
# and we handle the response via STATUS_TEXT messages
501-
self.master.mav.command_long_send( # type: ignore[union-attr] # pyright: ignore[reportAttributeAccessIssue]
502-
self.master.target_system, # type: ignore[union-attr] # pyright: ignore[reportAttributeAccessIssue]
503-
self.master.target_component, # type: ignore[union-attr] # pyright: ignore[reportAttributeAccessIssue]
501+
self.master.mav.command_long_send( # pyright: ignore[reportAttributeAccessIssue]
502+
self.master.target_system, # pyright: ignore[reportAttributeAccessIssue]
503+
self.master.target_component, # pyright: ignore[reportAttributeAccessIssue]
504504
mavutil.mavlink.MAV_CMD_DO_SEND_BANNER,
505505
0,
506506
0,
@@ -523,7 +523,7 @@ def _receive_banner_text(self) -> list[str]:
523523
start_time = time_time()
524524
banner_msgs: list[str] = []
525525
while self.master:
526-
msg = self.master.recv_match( # type: ignore[union-attr] # pyright: ignore[reportAttributeAccessIssue]
526+
msg = self.master.recv_match( # pyright: ignore[reportAttributeAccessIssue]
527527
type="STATUSTEXT", blocking=False
528528
)
529529
if msg:
@@ -551,7 +551,7 @@ def _request_message(self, message_id: int) -> None:
551551
system_id = int(self.info.system_id) if self.info.system_id else 0
552552
component_id = int(self.info.component_id) if self.info.component_id else 0
553553

554-
self.master.mav.command_long_send( # type: ignore[union-attr] # pyright: ignore[reportAttributeAccessIssue]
554+
self.master.mav.command_long_send( # pyright: ignore[reportAttributeAccessIssue]
555555
system_id,
556556
component_id,
557557
mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE,
@@ -870,7 +870,7 @@ def baudrate(self) -> int:
870870

871871
def set_master_for_testing(
872872
self,
873-
master: Optional[mavutil.mavlink_connection], # pyright: ignore[reportGeneralTypeIssues]
873+
master: Optional["MavlinkConnection"],
874874
) -> None:
875875
"""
876876
Set the MAVLink connection for testing purposes.

ardupilot_methodic_configurator/backend_flightcontroller_factory_mavftp.py

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

11-
from typing import Optional, Union
12-
13-
from pymavlink import mavutil
11+
from typing import TYPE_CHECKING, Optional, Union
1412

1513
from ardupilot_methodic_configurator.backend_mavftp import MAVFTP
1614

15+
if TYPE_CHECKING:
16+
from ardupilot_methodic_configurator.backend_flightcontroller_protocols import MavlinkConnection
17+
1718

18-
def create_mavftp(master: Union[mavutil.mavlink_connection, None]) -> MAVFTP: # pyright: ignore[reportGeneralTypeIssues]
19+
def create_mavftp(master: Union["MavlinkConnection", None]) -> MAVFTP:
1920
"""
2021
Factory function for creating MAVFTP instances.
2122
@@ -38,7 +39,7 @@ def create_mavftp(master: Union[mavutil.mavlink_connection, None]) -> MAVFTP: #
3839

3940

4041
def create_mavftp_safe(
41-
master: Union[mavutil.mavlink_connection, None], # pyright: ignore[reportGeneralTypeIssues]
42+
master: Union["MavlinkConnection", None],
4243
) -> Optional[MAVFTP]: # pyright: ignore[reportGeneralTypeIssues]
4344
"""
4445
Factory function for creating MAVFTP instances with safe error handling.

ardupilot_methodic_configurator/backend_flightcontroller_factory_mavlink.py

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

11-
from typing import Optional, Protocol
11+
from typing import TYPE_CHECKING, Optional, Protocol
1212

1313
from pymavlink import mavutil
1414

15+
if TYPE_CHECKING:
16+
from ardupilot_methodic_configurator.backend_flightcontroller_protocols import MavlinkConnection
17+
1518

1619
class MavlinkConnectionFactory(Protocol): # pylint: disable=too-few-public-methods
1720
"""Protocol for creating MAVLink connections."""
@@ -23,7 +26,7 @@ def create( # pylint: disable=too-many-arguments, too-many-positional-arguments
2326
timeout: float = 5.0,
2427
retries: int = 3,
2528
progress_callback: Optional[object] = None,
26-
) -> Optional[mavutil.mavlink_connection]: # pyright: ignore[reportGeneralTypeIssues]
29+
) -> Optional["MavlinkConnection"]:
2730
"""Create a MAVLink connection."""
2831
... # pylint: disable=unnecessary-ellipsis
2932

@@ -38,10 +41,10 @@ def create( # pylint: disable=too-many-arguments, too-many-positional-arguments
3841
timeout: float = 5.0,
3942
retries: int = 3,
4043
progress_callback: Optional[object] = None,
41-
) -> Optional[mavutil.mavlink_connection]: # pyright: ignore[reportGeneralTypeIssues]
44+
) -> Optional["MavlinkConnection"]:
4245
"""Create connection using actual PyMAVLink library."""
4346
try:
44-
return mavutil.mavlink_connection(
47+
return mavutil.mavlink_connection( # pyright: ignore[reportReturnType]
4548
device=device,
4649
baud=baudrate,
4750
timeout=timeout,

ardupilot_methodic_configurator/backend_flightcontroller_files.py

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -15,14 +15,15 @@
1515
from logging import warning as logging_warning
1616
from typing import TYPE_CHECKING, Callable, ClassVar, Optional, Union
1717

18-
from pymavlink import mavutil
19-
2018
from ardupilot_methodic_configurator import _
2119
from ardupilot_methodic_configurator.backend_flightcontroller_factory_mavftp import create_mavftp_safe
2220
from ardupilot_methodic_configurator.data_model_flightcontroller_info import FlightControllerInfo
2321

2422
if TYPE_CHECKING:
25-
from ardupilot_methodic_configurator.backend_flightcontroller_protocols import FlightControllerConnectionProtocol
23+
from ardupilot_methodic_configurator.backend_flightcontroller_protocols import (
24+
FlightControllerConnectionProtocol,
25+
MavlinkConnection,
26+
)
2627

2728
# Conditionally import MAVFTP if available
2829
try:
@@ -66,7 +67,7 @@ def __init__(
6667
self._connection_manager: FlightControllerConnectionProtocol = connection_manager
6768

6869
@property
69-
def master(self) -> Optional[mavutil.mavlink_connection]: # pyright: ignore[reportGeneralTypeIssues]
70+
def master(self) -> Optional["MavlinkConnection"]:
7071
"""Get master connection."""
7172
return self._connection_manager.master
7273

ardupilot_methodic_configurator/backend_flightcontroller_params.py

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -18,8 +18,6 @@
1818
from time import time as time_time
1919
from typing import TYPE_CHECKING, Any, Callable, Optional, Union
2020

21-
from pymavlink import mavutil
22-
2321
from ardupilot_methodic_configurator import _
2422
from ardupilot_methodic_configurator.backend_flightcontroller_connection import DEVICE_FC_PARAM_FROM_FILE
2523
from ardupilot_methodic_configurator.backend_flightcontroller_factory_mavftp import create_mavftp
@@ -28,7 +26,10 @@
2826

2927
# Type hint for connection manager to avoid circular imports
3028
if TYPE_CHECKING:
31-
from ardupilot_methodic_configurator.backend_flightcontroller_protocols import FlightControllerConnectionProtocol
29+
from ardupilot_methodic_configurator.backend_flightcontroller_protocols import (
30+
FlightControllerConnectionProtocol,
31+
MavlinkConnection,
32+
)
3233

3334

3435
class FlightControllerParams:
@@ -70,7 +71,7 @@ def __init__(
7071
self.fc_parameters: dict[str, float] = fc_parameters if fc_parameters is not None else {}
7172

7273
@property
73-
def master(self) -> Optional[mavutil.mavlink_connection]: # pyright: ignore[reportGeneralTypeIssues]
74+
def master(self) -> Optional["MavlinkConnection"]:
7475
"""Get master connection."""
7576
return self._connection_manager.master
7677

ardupilot_methodic_configurator/backend_flightcontroller_protocols.py

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,6 @@
3333
from ardupilot_methodic_configurator.data_model_par_dict import ParDict
3434

3535
# Type alias for MAVLink connection to avoid type checker issues
36-
# pymavlink.mavutil.mavlink_connection is actually a function that returns various connection types
3736
# We define MavlinkConnection as a protocol-like type to represent any MAVLink connection object
3837
if TYPE_CHECKING:
3938
# During type checking, import the actual mavutil module for better type hints
@@ -43,12 +42,13 @@
4342
# Use a union of known connection types for better type safety
4443
# Note: mavutil.mavlink_connection() returns different types based on the connection string
4544
MavlinkConnection = Union[
46-
mavutil.mavserial,
47-
mavutil.mavudp,
48-
mavutil.mavtcp,
49-
mavutil.mavtcpin,
50-
mavutil.mavmcast,
51-
object, # Fallback for other connection types
45+
mavutil.mavserial, # a serial mavlink port
46+
mavutil.mavudp, # a UDP mavlink socket
47+
mavutil.mavtcp, # a TCP mavlink socket
48+
mavutil.mavtcpin, # a TCP input mavlink socket
49+
mavutil.mavmcast, # a UDP multicast mavlink socket
50+
mavutil.mavwebsocket, # Mavlink WebSocket server, single client only
51+
mavutil.mavwebsocket_client, # client using WebSocket over TCP with WS and WSS support
5252
]
5353
else:
5454
# At runtime, we don't need the actual types

ardupilot_methodic_configurator/backend_mavftp.py

Lines changed: 51 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -217,6 +217,49 @@ def __setattr__(self, name, value) -> None:
217217
return
218218
raise AttributeError
219219

220+
def command(self, args: list[str]) -> None:
221+
"""
222+
Parse and apply 'set NAME VALUE' style arguments to update a setting.
223+
224+
args is expected to be [NAME, VALUE].
225+
"""
226+
if len(args) != 2:
227+
logging.error("Usage: ftp set <SETTING_NAME> <VALUE>")
228+
return
229+
230+
name, value_str = args
231+
232+
if name not in self._vars:
233+
logging.error("Unknown FTP setting '%s'", name)
234+
return
235+
236+
setting = self._vars[name]
237+
s_type = setting.type
238+
239+
# Only numeric (int/float) setting types are supported here, as documented.
240+
if s_type not in (int, float):
241+
logging.error(
242+
"FTP setting '%s' has unsupported type '%s' for CLI update (only int and float are supported)",
243+
name,
244+
getattr(s_type, "__name__", str(s_type)),
245+
)
246+
return
247+
248+
try:
249+
# Convert string to the appropriate type (int or float)
250+
converted = s_type(value_str)
251+
except (ValueError, TypeError):
252+
logging.error(
253+
"Invalid value '%s' for FTP setting '%s' (expected %s)",
254+
value_str,
255+
name,
256+
getattr(s_type, "__name__", str(s_type)),
257+
)
258+
return
259+
260+
setting.value = converted
261+
logging.info("FTP setting '%s' set to %s", name, converted)
262+
220263

221264
class MAVFTPReturn:
222265
"""The result of a MAVFTP operation."""
@@ -589,7 +632,7 @@ def __handle_open_ro_reply(self, op, _m) -> MAVFTPReturn:
589632
def __check_read_finished(self) -> bool:
590633
"""Check if download has completed."""
591634
# logging.debug("FTP: check_read_finished: %s %s", self.reached_eof, self.read_gaps)
592-
if self.reached_eof and len(self.read_gaps) == 0:
635+
if self.reached_eof and len(self.read_gaps) == 0 and self.fh is not None and self.op_start is not None:
593636
ofs = self.fh.tell()
594637
dt = time.time() - self.op_start
595638
rate = (ofs / dt) / 1024.0
@@ -674,7 +717,7 @@ def __handle_burst_read(self, op, _m) -> MAVFTPReturn: # noqa PRL0911, PGH004,
674717
if op.size > 0 and op.size < self.burst_size:
675718
# a burst complete with non-zero size and less than burst packet size
676719
# means EOF
677-
if not self.reached_eof and self.ftp_settings.debug > 0:
720+
if not self.reached_eof and self.ftp_settings.debug > 0 and self.op_start is not None:
678721
logging.info(
679722
"FTP: EOF at %u with %u gaps t=%.2f",
680723
self.fh.tell(),
@@ -700,7 +743,7 @@ def __handle_burst_read(self, op, _m) -> MAVFTPReturn: # noqa PRL0911, PGH004,
700743
if self.ftp_settings.debug > 0:
701744
logging.error("FTP: burst lost EOF %u %u", self.fh.tell(), op.offset)
702745
return MAVFTPReturn("BurstReadFile", ERR_Fail)
703-
if not self.reached_eof and self.ftp_settings.debug > 0:
746+
if not self.reached_eof and self.ftp_settings.debug > 0 and self.op_start is not None:
704747
logging.info(
705748
"FTP: EOF at %u with %u gaps t=%.2f", self.fh.tell(), len(self.read_gaps), time.time() - self.op_start
706749
)
@@ -809,7 +852,7 @@ def __put_finished(self, flen) -> None:
809852
if self.put_callback is not None:
810853
self.put_callback(flen)
811854
self.put_callback = None
812-
else:
855+
elif self.op_start is not None:
813856
dt = time.time() - self.op_start
814857
rate = (flen / dt) / 1024.0
815858
logging.info("Put %u bytes to %s file in %.2fs %.1fkByte/s", flen, self.filename, dt, rate)
@@ -829,7 +872,7 @@ def __handle_create_file_reply(self, op, _m) -> MAVFTPReturn:
829872

830873
def __send_more_writes(self) -> None:
831874
"""Send some more writes."""
832-
if len(self.write_list) == 0:
875+
if len(self.write_list) == 0 or self.write_list is None:
833876
# all done
834877
self.__put_finished(self.write_file_size)
835878
self.__terminate_session()
@@ -962,7 +1005,8 @@ def __handle_crc_reply(self, op, _m) -> MAVFTPReturn:
9621005
if op.opcode == OP_Ack and op.size == 4:
9631006
(crc,) = struct.unpack("<I", op.payload)
9641007
now = time.time()
965-
logging.info("crc: %s 0x%08x in %.1fs", self.filename, crc, now - self.op_start)
1008+
if self.op_start is not None:
1009+
logging.info("crc: %s 0x%08x in %.1fs", self.filename, crc, now - self.op_start)
9661010
return self.__decode_ftp_ack_and_nack(op)
9671011

9681012
def cmd_cancel(self) -> MAVFTPReturn:
@@ -972,7 +1016,7 @@ def cmd_cancel(self) -> MAVFTPReturn:
9721016

9731017
def cmd_status(self) -> MAVFTPReturn:
9741018
"""Show status."""
975-
if self.fh is None:
1019+
if self.fh is None or self.op_start is None:
9761020
logging.info("No transfer in progress")
9771021
else:
9781022
ofs = self.fh.tell()

0 commit comments

Comments
 (0)