From af03ae0a8b9be073107118bc63703bd2b8e8a39a Mon Sep 17 00:00:00 2001 From: David Vo Date: Tue, 12 Nov 2024 16:53:43 +1100 Subject: [PATCH] photonlibpy: Fix some type check failures (#1548) This fixes a variety of type check failures raised by both mypy and pyright. See #1548 --- photon-lib/py/photonlibpy/packet.py | 23 ++++++++++++------- photon-lib/py/photonlibpy/photonCamera.py | 3 ++- .../py/photonlibpy/targeting/TargetCorner.py | 6 ++++- .../targeting/multiTargetPNPResult.py | 8 +++++-- .../targeting/photonPipelineResult.py | 11 +++++---- .../targeting/photonTrackedTarget.py | 6 ++++- 6 files changed, 40 insertions(+), 17 deletions(-) diff --git a/photon-lib/py/photonlibpy/packet.py b/photon-lib/py/photonlibpy/packet.py index 0d3ecff53..8aae95062 100644 --- a/photon-lib/py/photonlibpy/packet.py +++ b/photon-lib/py/photonlibpy/packet.py @@ -16,11 +16,18 @@ ############################################################################### import struct -from typing import Any, Optional, Type +from typing import Generic, Optional, Protocol, TypeVar import wpilib from wpimath.geometry import Quaternion, Rotation3d, Transform3d, Translation3d +T = TypeVar("T") + + +class Serde(Generic[T], Protocol): + def pack(self, value: T) -> "Packet": ... + def unpack(self, packet: "Packet") -> T: ... + class Packet: def __init__(self, data: bytes = b""): @@ -34,9 +41,9 @@ class Packet: self.readPos = 0 self.outOfBytes = False - def clear(self): + def clear(self) -> None: """Clears the packet and resets the read and write positions.""" - self.packetData = [0] * self.size + self.packetData = bytes(self.size) self.readPos = 0 self.outOfBytes = False @@ -158,7 +165,7 @@ class Packet: ret.append(self.decodeDouble()) return ret - def decodeShortList(self) -> list[float]: + def decodeShortList(self) -> list[int]: """ * Returns a decoded array of shorts from the packet. """ @@ -187,14 +194,14 @@ class Packet: return Transform3d(translation, rotation) - def decodeList(self, serde: Type): + def decodeList(self, serde: Serde[T]) -> list[T]: retList = [] arr_len = self.decode8() for _ in range(arr_len): retList.append(serde.unpack(self)) return retList - def decodeOptional(self, serde: Type) -> Optional[Any]: + def decodeOptional(self, serde: Serde[T]) -> Optional[T]: if self.decodeBoolean(): return serde.unpack(self) else: @@ -281,7 +288,7 @@ class Packet: self.encodeDouble(quaternion.Y()) self.encodeDouble(quaternion.Z()) - def encodeList(self, values: list[Any], serde: Type): + def encodeList(self, values: list[T], serde: Serde[T]): """ Encodes a list of items using a specific serializer and appends it to the packet. """ @@ -291,7 +298,7 @@ class Packet: self.packetData = self.packetData + packed.getData() self.size = len(self.packetData) - def encodeOptional(self, value: Optional[Any], serde: Type): + def encodeOptional(self, value: Optional[T], serde: Serde[T]): """ Encodes an optional value using a specific serializer. """ diff --git a/photon-lib/py/photonlibpy/photonCamera.py b/photon-lib/py/photonlibpy/photonCamera.py index 7081463c2..18937cad1 100644 --- a/photon-lib/py/photonlibpy/photonCamera.py +++ b/photon-lib/py/photonlibpy/photonCamera.py @@ -233,12 +233,13 @@ class PhotonCamera: remoteUUID = self._rawBytesEntry.getTopic().getProperty("message_uuid") - if remoteUUID is None or len(remoteUUID) == 0: + if not remoteUUID: wpilib.reportWarning( f"PhotonVision coprocessor at path {self._path} has not reported a message interface UUID - is your coprocessor's camera started?", True, ) + assert isinstance(remoteUUID, str) # ntcore hands us a JSON string with leading/trailing quotes - remove those remoteUUID = remoteUUID.replace('"', "") diff --git a/photon-lib/py/photonlibpy/targeting/TargetCorner.py b/photon-lib/py/photonlibpy/targeting/TargetCorner.py index de58922c2..849a586eb 100644 --- a/photon-lib/py/photonlibpy/targeting/TargetCorner.py +++ b/photon-lib/py/photonlibpy/targeting/TargetCorner.py @@ -1,4 +1,8 @@ from dataclasses import dataclass +from typing import TYPE_CHECKING, ClassVar + +if TYPE_CHECKING: + from .. import generated @dataclass @@ -6,4 +10,4 @@ class TargetCorner: x: float = 0 y: float = 9 - photonStruct: "TargetCornerSerde" = None + photonStruct: ClassVar["generated.TargetCornerSerde"] diff --git a/photon-lib/py/photonlibpy/targeting/multiTargetPNPResult.py b/photon-lib/py/photonlibpy/targeting/multiTargetPNPResult.py index ad4233d62..55eca81c7 100644 --- a/photon-lib/py/photonlibpy/targeting/multiTargetPNPResult.py +++ b/photon-lib/py/photonlibpy/targeting/multiTargetPNPResult.py @@ -1,9 +1,13 @@ from dataclasses import dataclass, field +from typing import TYPE_CHECKING, ClassVar from wpimath.geometry import Transform3d from ..packet import Packet +if TYPE_CHECKING: + from .. import generated + @dataclass class PnpResult: @@ -13,7 +17,7 @@ class PnpResult: bestReprojErr: float = 0.0 altReprojErr: float = 0.0 - photonStruct: "PNPResultSerde" = None + photonStruct: ClassVar["generated.PnpResultSerde"] @dataclass @@ -33,4 +37,4 @@ class MultiTargetPNPResult: self.fiducialIDsUsed.append(fidId) return packet - photonStruct: "MultiTargetPNPResultSerde" = None + photonStruct: ClassVar["generated.MultiTargetPNPResultSerde"] diff --git a/photon-lib/py/photonlibpy/targeting/photonPipelineResult.py b/photon-lib/py/photonlibpy/targeting/photonPipelineResult.py index 07a175abb..67e722456 100644 --- a/photon-lib/py/photonlibpy/targeting/photonPipelineResult.py +++ b/photon-lib/py/photonlibpy/targeting/photonPipelineResult.py @@ -1,9 +1,12 @@ from dataclasses import dataclass, field -from typing import Optional +from typing import TYPE_CHECKING, ClassVar, Optional from .multiTargetPNPResult import MultiTargetPNPResult from .photonTrackedTarget import PhotonTrackedTarget +if TYPE_CHECKING: + from .. import generated + @dataclass class PhotonPipelineMetadata: @@ -17,7 +20,7 @@ class PhotonPipelineMetadata: timeSinceLastPong: int = -1 - photonStruct: "PhotonPipelineMetadataSerde" = None + photonStruct: ClassVar["generated.PhotonPipelineMetadataSerde"] @dataclass @@ -57,7 +60,7 @@ class PhotonPipelineResult: def hasTargets(self) -> bool: return len(self.targets) > 0 - def getBestTarget(self) -> PhotonTrackedTarget: + def getBestTarget(self) -> Optional[PhotonTrackedTarget]: """ Returns the best target in this pipeline result. If there are no targets, this method will return null. The best target is determined by the target sort mode in the PhotonVision UI. @@ -66,4 +69,4 @@ class PhotonPipelineResult: return None return self.getTargets()[0] - photonStruct: "PhotonPipelineResultSerde" = None + photonStruct: ClassVar["generated.PhotonPipelineResultSerde"] diff --git a/photon-lib/py/photonlibpy/targeting/photonTrackedTarget.py b/photon-lib/py/photonlibpy/targeting/photonTrackedTarget.py index 16a4c3554..4ad3668a5 100644 --- a/photon-lib/py/photonlibpy/targeting/photonTrackedTarget.py +++ b/photon-lib/py/photonlibpy/targeting/photonTrackedTarget.py @@ -1,10 +1,14 @@ from dataclasses import dataclass, field +from typing import TYPE_CHECKING, ClassVar from wpimath.geometry import Transform3d from ..packet import Packet from .TargetCorner import TargetCorner +if TYPE_CHECKING: + from .. import generated + @dataclass class PhotonTrackedTarget: @@ -59,4 +63,4 @@ class PhotonTrackedTarget: retList.append(TargetCorner(cx, cy)) return retList - photonStruct: "PhotonTrackedTargetSerde" = None + photonStruct: ClassVar["generated.PhotonTrackedTargetSerde"]