photonlibpy 2024.3.1__py3-none-any.whl → 2025.0.0a0__py3-none-any.whl
Sign up to get free protection for your applications and to get access to all the features.
- photonlibpy/__init__.py +21 -1
- photonlibpy/estimatedRobotPose.py +18 -1
- photonlibpy/generated/MultiTargetPNPResultSerde.py +45 -0
- photonlibpy/generated/PhotonPipelineMetadataSerde.py +50 -0
- photonlibpy/generated/PhotonPipelineResultSerde.py +48 -0
- photonlibpy/generated/PhotonTrackedTargetSerde.py +73 -0
- photonlibpy/generated/PnpResultSerde.py +52 -0
- photonlibpy/generated/TargetCornerSerde.py +45 -0
- photonlibpy/generated/__init__.py +9 -0
- photonlibpy/packet.py +67 -10
- photonlibpy/photonCamera.py +90 -15
- photonlibpy/photonPoseEstimator.py +26 -7
- photonlibpy/targeting/TargetCorner.py +9 -0
- photonlibpy/targeting/__init__.py +6 -0
- photonlibpy/targeting/multiTargetPNPResult.py +34 -0
- photonlibpy/targeting/photonPipelineResult.py +65 -0
- photonlibpy/{photonTrackedTarget.py → targeting/photonTrackedTarget.py} +3 -27
- photonlibpy/version.py +2 -2
- photonlibpy-2025.0.0a0.dist-info/METADATA +13 -0
- photonlibpy-2025.0.0a0.dist-info/RECORD +22 -0
- {photonlibpy-2024.3.1.dist-info → photonlibpy-2025.0.0a0.dist-info}/WHEEL +1 -1
- photonlibpy/multiTargetPNPResult.py +0 -49
- photonlibpy/photonPipelineResult.py +0 -43
- photonlibpy-2024.3.1.dist-info/METADATA +0 -13
- photonlibpy-2024.3.1.dist-info/RECORD +0 -13
- {photonlibpy-2024.3.1.dist-info → photonlibpy-2025.0.0a0.dist-info}/top_level.txt +0 -0
photonlibpy/__init__.py
CHANGED
@@ -1 +1,21 @@
|
|
1
|
-
|
1
|
+
###############################################################################
|
2
|
+
## Copyright (C) Photon Vision.
|
3
|
+
###############################################################################
|
4
|
+
## This program is free software: you can redistribute it and/or modify
|
5
|
+
## it under the terms of the GNU General Public License as published by
|
6
|
+
## the Free Software Foundation, either version 3 of the License, or
|
7
|
+
## (at your option) any later version.
|
8
|
+
##
|
9
|
+
## This program is distributed in the hope that it will be useful,
|
10
|
+
## but WITHOUT ANY WARRANTY; without even the implied warranty of
|
11
|
+
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
12
|
+
## GNU General Public License for more details.
|
13
|
+
##
|
14
|
+
## You should have received a copy of the GNU General Public License
|
15
|
+
## along with this program. If not, see <https://www.gnu.org/licenses/>.
|
16
|
+
###############################################################################
|
17
|
+
|
18
|
+
from .packet import Packet # noqa
|
19
|
+
from .estimatedRobotPose import EstimatedRobotPose # noqa
|
20
|
+
from .photonPoseEstimator import PhotonPoseEstimator, PoseStrategy # noqa
|
21
|
+
from .photonCamera import PhotonCamera # noqa
|
@@ -1,9 +1,26 @@
|
|
1
|
+
###############################################################################
|
2
|
+
## Copyright (C) Photon Vision.
|
3
|
+
###############################################################################
|
4
|
+
## This program is free software: you can redistribute it and/or modify
|
5
|
+
## it under the terms of the GNU General Public License as published by
|
6
|
+
## the Free Software Foundation, either version 3 of the License, or
|
7
|
+
## (at your option) any later version.
|
8
|
+
##
|
9
|
+
## This program is distributed in the hope that it will be useful,
|
10
|
+
## but WITHOUT ANY WARRANTY; without even the implied warranty of
|
11
|
+
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
12
|
+
## GNU General Public License for more details.
|
13
|
+
##
|
14
|
+
## You should have received a copy of the GNU General Public License
|
15
|
+
## along with this program. If not, see <https://www.gnu.org/licenses/>.
|
16
|
+
###############################################################################
|
17
|
+
|
1
18
|
from dataclasses import dataclass
|
2
19
|
from typing import TYPE_CHECKING
|
3
20
|
|
4
21
|
from wpimath.geometry import Pose3d
|
5
22
|
|
6
|
-
from .photonTrackedTarget import PhotonTrackedTarget
|
23
|
+
from .targeting.photonTrackedTarget import PhotonTrackedTarget
|
7
24
|
|
8
25
|
if TYPE_CHECKING:
|
9
26
|
from .photonPoseEstimator import PoseStrategy
|
@@ -0,0 +1,45 @@
|
|
1
|
+
###############################################################################
|
2
|
+
## Copyright (C) Photon Vision.
|
3
|
+
###############################################################################
|
4
|
+
## This program is free software: you can redistribute it and/or modify
|
5
|
+
## it under the terms of the GNU General Public License as published by
|
6
|
+
## the Free Software Foundation, either version 3 of the License, or
|
7
|
+
## (at your option) any later version.
|
8
|
+
##
|
9
|
+
## This program is distributed in the hope that it will be useful,
|
10
|
+
## but WITHOUT ANY WARRANTY; without even the implied warranty of
|
11
|
+
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
12
|
+
## GNU General Public License for more details.
|
13
|
+
##
|
14
|
+
## You should have received a copy of the GNU General Public License
|
15
|
+
## along with this program. If not, see <https://www.gnu.org/licenses/>.
|
16
|
+
###############################################################################
|
17
|
+
|
18
|
+
###############################################################################
|
19
|
+
## THIS FILE WAS AUTO-GENERATED BY ./photon-serde/generate_messages.py.
|
20
|
+
## --> DO NOT MODIFY <--
|
21
|
+
###############################################################################
|
22
|
+
|
23
|
+
from ..targeting import *
|
24
|
+
|
25
|
+
|
26
|
+
class MultiTargetPNPResultSerde:
|
27
|
+
# Message definition md5sum. See photon_packet.adoc for details
|
28
|
+
MESSAGE_VERSION = "541096947e9f3ca2d3f425ff7b04aa7b"
|
29
|
+
MESSAGE_FORMAT = "PnpResult:ae4d655c0a3104d88df4f5db144c1e86 estimatedPose;int16 fiducialIDsUsed[?];"
|
30
|
+
|
31
|
+
@staticmethod
|
32
|
+
def unpack(packet: "Packet") -> "MultiTargetPNPResult":
|
33
|
+
ret = MultiTargetPNPResult()
|
34
|
+
|
35
|
+
# estimatedPose is of non-intrinsic type PnpResult
|
36
|
+
ret.estimatedPose = PnpResult.photonStruct.unpack(packet)
|
37
|
+
|
38
|
+
# fiducialIDsUsed is a custom VLA!
|
39
|
+
ret.fiducialIDsUsed = packet.decodeShortList()
|
40
|
+
|
41
|
+
return ret
|
42
|
+
|
43
|
+
|
44
|
+
# Hack ourselves into the base class
|
45
|
+
MultiTargetPNPResult.photonStruct = MultiTargetPNPResultSerde()
|
@@ -0,0 +1,50 @@
|
|
1
|
+
###############################################################################
|
2
|
+
## Copyright (C) Photon Vision.
|
3
|
+
###############################################################################
|
4
|
+
## This program is free software: you can redistribute it and/or modify
|
5
|
+
## it under the terms of the GNU General Public License as published by
|
6
|
+
## the Free Software Foundation, either version 3 of the License, or
|
7
|
+
## (at your option) any later version.
|
8
|
+
##
|
9
|
+
## This program is distributed in the hope that it will be useful,
|
10
|
+
## but WITHOUT ANY WARRANTY; without even the implied warranty of
|
11
|
+
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
12
|
+
## GNU General Public License for more details.
|
13
|
+
##
|
14
|
+
## You should have received a copy of the GNU General Public License
|
15
|
+
## along with this program. If not, see <https://www.gnu.org/licenses/>.
|
16
|
+
###############################################################################
|
17
|
+
|
18
|
+
###############################################################################
|
19
|
+
## THIS FILE WAS AUTO-GENERATED BY ./photon-serde/generate_messages.py.
|
20
|
+
## --> DO NOT MODIFY <--
|
21
|
+
###############################################################################
|
22
|
+
|
23
|
+
from ..targeting import *
|
24
|
+
|
25
|
+
|
26
|
+
class PhotonPipelineMetadataSerde:
|
27
|
+
# Message definition md5sum. See photon_packet.adoc for details
|
28
|
+
MESSAGE_VERSION = "626e70461cbdb274fb43ead09c255f4e"
|
29
|
+
MESSAGE_FORMAT = (
|
30
|
+
"int64 sequenceID;int64 captureTimestampMicros;int64 publishTimestampMicros;"
|
31
|
+
)
|
32
|
+
|
33
|
+
@staticmethod
|
34
|
+
def unpack(packet: "Packet") -> "PhotonPipelineMetadata":
|
35
|
+
ret = PhotonPipelineMetadata()
|
36
|
+
|
37
|
+
# sequenceID is of intrinsic type int64
|
38
|
+
ret.sequenceID = packet.decodeLong()
|
39
|
+
|
40
|
+
# captureTimestampMicros is of intrinsic type int64
|
41
|
+
ret.captureTimestampMicros = packet.decodeLong()
|
42
|
+
|
43
|
+
# publishTimestampMicros is of intrinsic type int64
|
44
|
+
ret.publishTimestampMicros = packet.decodeLong()
|
45
|
+
|
46
|
+
return ret
|
47
|
+
|
48
|
+
|
49
|
+
# Hack ourselves into the base class
|
50
|
+
PhotonPipelineMetadata.photonStruct = PhotonPipelineMetadataSerde()
|
@@ -0,0 +1,48 @@
|
|
1
|
+
###############################################################################
|
2
|
+
## Copyright (C) Photon Vision.
|
3
|
+
###############################################################################
|
4
|
+
## This program is free software: you can redistribute it and/or modify
|
5
|
+
## it under the terms of the GNU General Public License as published by
|
6
|
+
## the Free Software Foundation, either version 3 of the License, or
|
7
|
+
## (at your option) any later version.
|
8
|
+
##
|
9
|
+
## This program is distributed in the hope that it will be useful,
|
10
|
+
## but WITHOUT ANY WARRANTY; without even the implied warranty of
|
11
|
+
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
12
|
+
## GNU General Public License for more details.
|
13
|
+
##
|
14
|
+
## You should have received a copy of the GNU General Public License
|
15
|
+
## along with this program. If not, see <https://www.gnu.org/licenses/>.
|
16
|
+
###############################################################################
|
17
|
+
|
18
|
+
###############################################################################
|
19
|
+
## THIS FILE WAS AUTO-GENERATED BY ./photon-serde/generate_messages.py.
|
20
|
+
## --> DO NOT MODIFY <--
|
21
|
+
###############################################################################
|
22
|
+
|
23
|
+
from ..targeting import *
|
24
|
+
|
25
|
+
|
26
|
+
class PhotonPipelineResultSerde:
|
27
|
+
# Message definition md5sum. See photon_packet.adoc for details
|
28
|
+
MESSAGE_VERSION = "5eeaa293d0c69aea90eaddea786a2b3b"
|
29
|
+
MESSAGE_FORMAT = "PhotonPipelineMetadata:626e70461cbdb274fb43ead09c255f4e metadata;PhotonTrackedTarget:cc6dbb5c5c1e0fa808108019b20863f1 targets[?];optional MultiTargetPNPResult:541096947e9f3ca2d3f425ff7b04aa7b multitagResult;"
|
30
|
+
|
31
|
+
@staticmethod
|
32
|
+
def unpack(packet: "Packet") -> "PhotonPipelineResult":
|
33
|
+
ret = PhotonPipelineResult()
|
34
|
+
|
35
|
+
# metadata is of non-intrinsic type PhotonPipelineMetadata
|
36
|
+
ret.metadata = PhotonPipelineMetadata.photonStruct.unpack(packet)
|
37
|
+
|
38
|
+
# targets is a custom VLA!
|
39
|
+
ret.targets = packet.decodeList(PhotonTrackedTarget.photonStruct)
|
40
|
+
|
41
|
+
# multitagResult is optional! it better not be a VLA too
|
42
|
+
ret.multitagResult = packet.decodeOptional(MultiTargetPNPResult.photonStruct)
|
43
|
+
|
44
|
+
return ret
|
45
|
+
|
46
|
+
|
47
|
+
# Hack ourselves into the base class
|
48
|
+
PhotonPipelineResult.photonStruct = PhotonPipelineResultSerde()
|
@@ -0,0 +1,73 @@
|
|
1
|
+
###############################################################################
|
2
|
+
## Copyright (C) Photon Vision.
|
3
|
+
###############################################################################
|
4
|
+
## This program is free software: you can redistribute it and/or modify
|
5
|
+
## it under the terms of the GNU General Public License as published by
|
6
|
+
## the Free Software Foundation, either version 3 of the License, or
|
7
|
+
## (at your option) any later version.
|
8
|
+
##
|
9
|
+
## This program is distributed in the hope that it will be useful,
|
10
|
+
## but WITHOUT ANY WARRANTY; without even the implied warranty of
|
11
|
+
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
12
|
+
## GNU General Public License for more details.
|
13
|
+
##
|
14
|
+
## You should have received a copy of the GNU General Public License
|
15
|
+
## along with this program. If not, see <https://www.gnu.org/licenses/>.
|
16
|
+
###############################################################################
|
17
|
+
|
18
|
+
###############################################################################
|
19
|
+
## THIS FILE WAS AUTO-GENERATED BY ./photon-serde/generate_messages.py.
|
20
|
+
## --> DO NOT MODIFY <--
|
21
|
+
###############################################################################
|
22
|
+
|
23
|
+
from ..targeting import *
|
24
|
+
|
25
|
+
|
26
|
+
class PhotonTrackedTargetSerde:
|
27
|
+
# Message definition md5sum. See photon_packet.adoc for details
|
28
|
+
MESSAGE_VERSION = "cc6dbb5c5c1e0fa808108019b20863f1"
|
29
|
+
MESSAGE_FORMAT = "float64 yaw;float64 pitch;float64 area;float64 skew;int32 fiducialId;int32 objDetectId;float32 objDetectConf;Transform3d bestCameraToTarget;Transform3d altCameraToTarget;float64 poseAmbiguity;TargetCorner:16f6ac0dedc8eaccb951f4895d9e18b6 minAreaRectCorners[?];TargetCorner:16f6ac0dedc8eaccb951f4895d9e18b6 detectedCorners[?];"
|
30
|
+
|
31
|
+
@staticmethod
|
32
|
+
def unpack(packet: "Packet") -> "PhotonTrackedTarget":
|
33
|
+
ret = PhotonTrackedTarget()
|
34
|
+
|
35
|
+
# yaw is of intrinsic type float64
|
36
|
+
ret.yaw = packet.decodeDouble()
|
37
|
+
|
38
|
+
# pitch is of intrinsic type float64
|
39
|
+
ret.pitch = packet.decodeDouble()
|
40
|
+
|
41
|
+
# area is of intrinsic type float64
|
42
|
+
ret.area = packet.decodeDouble()
|
43
|
+
|
44
|
+
# skew is of intrinsic type float64
|
45
|
+
ret.skew = packet.decodeDouble()
|
46
|
+
|
47
|
+
# fiducialId is of intrinsic type int32
|
48
|
+
ret.fiducialId = packet.decodeInt()
|
49
|
+
|
50
|
+
# objDetectId is of intrinsic type int32
|
51
|
+
ret.objDetectId = packet.decodeInt()
|
52
|
+
|
53
|
+
# objDetectConf is of intrinsic type float32
|
54
|
+
ret.objDetectConf = packet.decodeFloat()
|
55
|
+
|
56
|
+
ret.bestCameraToTarget = packet.decodeTransform()
|
57
|
+
|
58
|
+
ret.altCameraToTarget = packet.decodeTransform()
|
59
|
+
|
60
|
+
# poseAmbiguity is of intrinsic type float64
|
61
|
+
ret.poseAmbiguity = packet.decodeDouble()
|
62
|
+
|
63
|
+
# minAreaRectCorners is a custom VLA!
|
64
|
+
ret.minAreaRectCorners = packet.decodeList(TargetCorner.photonStruct)
|
65
|
+
|
66
|
+
# detectedCorners is a custom VLA!
|
67
|
+
ret.detectedCorners = packet.decodeList(TargetCorner.photonStruct)
|
68
|
+
|
69
|
+
return ret
|
70
|
+
|
71
|
+
|
72
|
+
# Hack ourselves into the base class
|
73
|
+
PhotonTrackedTarget.photonStruct = PhotonTrackedTargetSerde()
|
@@ -0,0 +1,52 @@
|
|
1
|
+
###############################################################################
|
2
|
+
## Copyright (C) Photon Vision.
|
3
|
+
###############################################################################
|
4
|
+
## This program is free software: you can redistribute it and/or modify
|
5
|
+
## it under the terms of the GNU General Public License as published by
|
6
|
+
## the Free Software Foundation, either version 3 of the License, or
|
7
|
+
## (at your option) any later version.
|
8
|
+
##
|
9
|
+
## This program is distributed in the hope that it will be useful,
|
10
|
+
## but WITHOUT ANY WARRANTY; without even the implied warranty of
|
11
|
+
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
12
|
+
## GNU General Public License for more details.
|
13
|
+
##
|
14
|
+
## You should have received a copy of the GNU General Public License
|
15
|
+
## along with this program. If not, see <https://www.gnu.org/licenses/>.
|
16
|
+
###############################################################################
|
17
|
+
|
18
|
+
###############################################################################
|
19
|
+
## THIS FILE WAS AUTO-GENERATED BY ./photon-serde/generate_messages.py.
|
20
|
+
## --> DO NOT MODIFY <--
|
21
|
+
###############################################################################
|
22
|
+
|
23
|
+
from ..targeting import *
|
24
|
+
|
25
|
+
|
26
|
+
class PnpResultSerde:
|
27
|
+
# Message definition md5sum. See photon_packet.adoc for details
|
28
|
+
MESSAGE_VERSION = "ae4d655c0a3104d88df4f5db144c1e86"
|
29
|
+
MESSAGE_FORMAT = "Transform3d best;Transform3d alt;float64 bestReprojErr;float64 altReprojErr;float64 ambiguity;"
|
30
|
+
|
31
|
+
@staticmethod
|
32
|
+
def unpack(packet: "Packet") -> "PnpResult":
|
33
|
+
ret = PnpResult()
|
34
|
+
|
35
|
+
ret.best = packet.decodeTransform()
|
36
|
+
|
37
|
+
ret.alt = packet.decodeTransform()
|
38
|
+
|
39
|
+
# bestReprojErr is of intrinsic type float64
|
40
|
+
ret.bestReprojErr = packet.decodeDouble()
|
41
|
+
|
42
|
+
# altReprojErr is of intrinsic type float64
|
43
|
+
ret.altReprojErr = packet.decodeDouble()
|
44
|
+
|
45
|
+
# ambiguity is of intrinsic type float64
|
46
|
+
ret.ambiguity = packet.decodeDouble()
|
47
|
+
|
48
|
+
return ret
|
49
|
+
|
50
|
+
|
51
|
+
# Hack ourselves into the base class
|
52
|
+
PnpResult.photonStruct = PnpResultSerde()
|
@@ -0,0 +1,45 @@
|
|
1
|
+
###############################################################################
|
2
|
+
## Copyright (C) Photon Vision.
|
3
|
+
###############################################################################
|
4
|
+
## This program is free software: you can redistribute it and/or modify
|
5
|
+
## it under the terms of the GNU General Public License as published by
|
6
|
+
## the Free Software Foundation, either version 3 of the License, or
|
7
|
+
## (at your option) any later version.
|
8
|
+
##
|
9
|
+
## This program is distributed in the hope that it will be useful,
|
10
|
+
## but WITHOUT ANY WARRANTY; without even the implied warranty of
|
11
|
+
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
12
|
+
## GNU General Public License for more details.
|
13
|
+
##
|
14
|
+
## You should have received a copy of the GNU General Public License
|
15
|
+
## along with this program. If not, see <https://www.gnu.org/licenses/>.
|
16
|
+
###############################################################################
|
17
|
+
|
18
|
+
###############################################################################
|
19
|
+
## THIS FILE WAS AUTO-GENERATED BY ./photon-serde/generate_messages.py.
|
20
|
+
## --> DO NOT MODIFY <--
|
21
|
+
###############################################################################
|
22
|
+
|
23
|
+
from ..targeting import *
|
24
|
+
|
25
|
+
|
26
|
+
class TargetCornerSerde:
|
27
|
+
# Message definition md5sum. See photon_packet.adoc for details
|
28
|
+
MESSAGE_VERSION = "16f6ac0dedc8eaccb951f4895d9e18b6"
|
29
|
+
MESSAGE_FORMAT = "float64 x;float64 y;"
|
30
|
+
|
31
|
+
@staticmethod
|
32
|
+
def unpack(packet: "Packet") -> "TargetCorner":
|
33
|
+
ret = TargetCorner()
|
34
|
+
|
35
|
+
# x is of intrinsic type float64
|
36
|
+
ret.x = packet.decodeDouble()
|
37
|
+
|
38
|
+
# y is of intrinsic type float64
|
39
|
+
ret.y = packet.decodeDouble()
|
40
|
+
|
41
|
+
return ret
|
42
|
+
|
43
|
+
|
44
|
+
# Hack ourselves into the base class
|
45
|
+
TargetCorner.photonStruct = TargetCornerSerde()
|
@@ -0,0 +1,9 @@
|
|
1
|
+
# no one but us chickens
|
2
|
+
|
3
|
+
from .MultiTargetPNPResultSerde import MultiTargetPNPResultSerde # noqa
|
4
|
+
from .PhotonPipelineMetadataSerde import PhotonPipelineMetadataSerde # noqa
|
5
|
+
from .PhotonPipelineMetadataSerde import PhotonPipelineMetadataSerde # noqa
|
6
|
+
from .PhotonPipelineResultSerde import PhotonPipelineResultSerde # noqa
|
7
|
+
from .PhotonTrackedTargetSerde import PhotonTrackedTargetSerde # noqa
|
8
|
+
from .PnpResultSerde import PnpResultSerde # noqa
|
9
|
+
from .TargetCornerSerde import TargetCornerSerde # noqa
|
photonlibpy/packet.py
CHANGED
@@ -1,4 +1,22 @@
|
|
1
|
+
###############################################################################
|
2
|
+
## Copyright (C) Photon Vision.
|
3
|
+
###############################################################################
|
4
|
+
## This program is free software: you can redistribute it and/or modify
|
5
|
+
## it under the terms of the GNU General Public License as published by
|
6
|
+
## the Free Software Foundation, either version 3 of the License, or
|
7
|
+
## (at your option) any later version.
|
8
|
+
##
|
9
|
+
## This program is distributed in the hope that it will be useful,
|
10
|
+
## but WITHOUT ANY WARRANTY; without even the implied warranty of
|
11
|
+
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
12
|
+
## GNU General Public License for more details.
|
13
|
+
##
|
14
|
+
## You should have received a copy of the GNU General Public License
|
15
|
+
## along with this program. If not, see <https://www.gnu.org/licenses/>.
|
16
|
+
###############################################################################
|
17
|
+
|
1
18
|
import struct
|
19
|
+
from typing import Any, Optional, Type
|
2
20
|
from wpimath.geometry import Transform3d, Translation3d, Rotation3d, Quaternion
|
3
21
|
import wpilib
|
4
22
|
|
@@ -67,7 +85,9 @@ class Packet:
|
|
67
85
|
for _ in range(numBytes):
|
68
86
|
intList.append(self._getNextByteAsInt())
|
69
87
|
|
70
|
-
# Interpret the bytes as
|
88
|
+
# Interpret the bytes as the requested type.
|
89
|
+
# Note due to NT's byte order assumptions,
|
90
|
+
# we have to flip the order of intList
|
71
91
|
value = struct.unpack(unpackFormat, bytes(intList))[0]
|
72
92
|
|
73
93
|
return value
|
@@ -78,23 +98,39 @@ class Packet:
|
|
78
98
|
*
|
79
99
|
* @return A decoded byte from the packet.
|
80
100
|
"""
|
81
|
-
return self._decodeGeneric("
|
101
|
+
return self._decodeGeneric("<b", 1)
|
82
102
|
|
83
103
|
def decode16(self) -> int:
|
84
104
|
"""
|
85
|
-
* Returns a single decoded
|
105
|
+
* Returns a single decoded short from the packet.
|
86
106
|
*
|
87
|
-
* @return A decoded
|
107
|
+
* @return A decoded short from the packet.
|
88
108
|
"""
|
89
|
-
return self._decodeGeneric("
|
109
|
+
return self._decodeGeneric("<h", 2)
|
90
110
|
|
91
|
-
def
|
111
|
+
def decodeInt(self) -> int:
|
92
112
|
"""
|
93
113
|
* Returns a decoded int (32 bytes) from the packet.
|
94
114
|
*
|
95
115
|
* @return A decoded int from the packet.
|
96
116
|
"""
|
97
|
-
return self._decodeGeneric("
|
117
|
+
return self._decodeGeneric("<l", 4)
|
118
|
+
|
119
|
+
def decodeFloat(self) -> float:
|
120
|
+
"""
|
121
|
+
* Returns a decoded float from the packet.
|
122
|
+
*
|
123
|
+
* @return A decoded float from the packet.
|
124
|
+
"""
|
125
|
+
return self._decodeGeneric("<f", 4)
|
126
|
+
|
127
|
+
def decodeLong(self) -> int:
|
128
|
+
"""
|
129
|
+
* Returns a decoded int64 from the packet.
|
130
|
+
*
|
131
|
+
* @return A decoded int64 from the packet.
|
132
|
+
"""
|
133
|
+
return self._decodeGeneric("<q", 8)
|
98
134
|
|
99
135
|
def decodeDouble(self) -> float:
|
100
136
|
"""
|
@@ -102,7 +138,7 @@ class Packet:
|
|
102
138
|
*
|
103
139
|
* @return A decoded double from the packet.
|
104
140
|
"""
|
105
|
-
return self._decodeGeneric("
|
141
|
+
return self._decodeGeneric("<d", 8)
|
106
142
|
|
107
143
|
def decodeBoolean(self) -> bool:
|
108
144
|
"""
|
@@ -115,14 +151,22 @@ class Packet:
|
|
115
151
|
def decodeDoubleArray(self, length: int) -> list[float]:
|
116
152
|
"""
|
117
153
|
* Returns a decoded array of floats from the packet.
|
118
|
-
*
|
119
|
-
* @return A decoded array of floats from the packet.
|
120
154
|
"""
|
121
155
|
ret = []
|
122
156
|
for _ in range(length):
|
123
157
|
ret.append(self.decodeDouble())
|
124
158
|
return ret
|
125
159
|
|
160
|
+
def decodeShortList(self) -> list[float]:
|
161
|
+
"""
|
162
|
+
* Returns a decoded array of shorts from the packet.
|
163
|
+
"""
|
164
|
+
length = self.decode8()
|
165
|
+
ret = []
|
166
|
+
for _ in range(length):
|
167
|
+
ret.append(self.decode16())
|
168
|
+
return ret
|
169
|
+
|
126
170
|
def decodeTransform(self) -> Transform3d:
|
127
171
|
"""
|
128
172
|
* Returns a decoded Transform3d
|
@@ -141,3 +185,16 @@ class Packet:
|
|
141
185
|
rotation = Rotation3d(Quaternion(w, x, y, z))
|
142
186
|
|
143
187
|
return Transform3d(translation, rotation)
|
188
|
+
|
189
|
+
def decodeList(self, serde: Type):
|
190
|
+
retList = []
|
191
|
+
arr_len = self.decode8()
|
192
|
+
for _ in range(arr_len):
|
193
|
+
retList.append(serde.unpack(self))
|
194
|
+
return retList
|
195
|
+
|
196
|
+
def decodeOptional(self, serde: Type) -> Optional[Any]:
|
197
|
+
if self.decodeBoolean():
|
198
|
+
return serde.unpack(self)
|
199
|
+
else:
|
200
|
+
return None
|
photonlibpy/photonCamera.py
CHANGED
@@ -1,10 +1,31 @@
|
|
1
|
+
###############################################################################
|
2
|
+
## Copyright (C) Photon Vision.
|
3
|
+
###############################################################################
|
4
|
+
## This program is free software: you can redistribute it and/or modify
|
5
|
+
## it under the terms of the GNU General Public License as published by
|
6
|
+
## the Free Software Foundation, either version 3 of the License, or
|
7
|
+
## (at your option) any later version.
|
8
|
+
##
|
9
|
+
## This program is distributed in the hope that it will be useful,
|
10
|
+
## but WITHOUT ANY WARRANTY; without even the implied warranty of
|
11
|
+
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
12
|
+
## GNU General Public License for more details.
|
13
|
+
##
|
14
|
+
## You should have received a copy of the GNU General Public License
|
15
|
+
## along with this program. If not, see <https://www.gnu.org/licenses/>.
|
16
|
+
###############################################################################
|
17
|
+
|
1
18
|
from enum import Enum
|
19
|
+
from typing import List
|
2
20
|
import ntcore
|
3
|
-
from wpilib import Timer
|
21
|
+
from wpilib import RobotController, Timer
|
4
22
|
import wpilib
|
5
|
-
from
|
6
|
-
from
|
7
|
-
from
|
23
|
+
from .packet import Packet
|
24
|
+
from .targeting.photonPipelineResult import PhotonPipelineResult
|
25
|
+
from .version import PHOTONVISION_VERSION, PHOTONLIB_VERSION # type: ignore[import-untyped]
|
26
|
+
|
27
|
+
# magical import to make serde stuff work
|
28
|
+
import photonlibpy.generated # noqa
|
8
29
|
|
9
30
|
|
10
31
|
class VisionLEDMode(Enum):
|
@@ -32,7 +53,9 @@ class PhotonCamera:
|
|
32
53
|
self._cameraTable = photonvision_root_table.getSubTable(cameraName)
|
33
54
|
self._path = self._cameraTable.getPath()
|
34
55
|
self._rawBytesEntry = self._cameraTable.getRawTopic("rawBytes").subscribe(
|
35
|
-
"
|
56
|
+
f"photonstruct:PhotonPipelineResult:{PhotonPipelineResult.photonStruct.MESSAGE_VERSION}",
|
57
|
+
bytes([]),
|
58
|
+
ntcore.PubSubOptions(periodic=0.01, sendAll=True),
|
36
59
|
)
|
37
60
|
|
38
61
|
self._driverModePublisher = self._cameraTable.getBooleanTopic(
|
@@ -75,23 +98,52 @@ class PhotonCamera:
|
|
75
98
|
self._prevHeartbeat = 0
|
76
99
|
self._prevHeartbeatChangeTime = Timer.getFPGATimestamp()
|
77
100
|
|
101
|
+
def getAllUnreadResults(self) -> List[PhotonPipelineResult]:
|
102
|
+
"""
|
103
|
+
The list of pipeline results sent by PhotonVision since the last call to getAllUnreadResults().
|
104
|
+
Calling this function clears the internal FIFO queue, and multiple calls to
|
105
|
+
getAllUnreadResults() will return different (potentially empty) result arrays. Be careful to
|
106
|
+
call this exactly ONCE per loop of your robot code! FIFO depth is limited to 20 changes, so
|
107
|
+
make sure to call this frequently enough to avoid old results being discarded, too!
|
108
|
+
"""
|
109
|
+
|
110
|
+
self._versionCheck()
|
111
|
+
|
112
|
+
changes = self._rawBytesEntry.readQueue()
|
113
|
+
|
114
|
+
ret = []
|
115
|
+
|
116
|
+
for change in changes:
|
117
|
+
byteList = change.value
|
118
|
+
timestamp = change.time
|
119
|
+
|
120
|
+
if len(byteList) < 1:
|
121
|
+
pass
|
122
|
+
else:
|
123
|
+
newResult = PhotonPipelineResult()
|
124
|
+
pkt = Packet(byteList)
|
125
|
+
newResult = PhotonPipelineResult.photonStruct.unpack(pkt)
|
126
|
+
# NT4 allows us to correct the timestamp based on when the message was sent
|
127
|
+
newResult.ntReceiveTimestampMicros = timestamp / 1e6
|
128
|
+
ret.append(newResult)
|
129
|
+
|
130
|
+
return ret
|
131
|
+
|
78
132
|
def getLatestResult(self) -> PhotonPipelineResult:
|
79
133
|
self._versionCheck()
|
80
134
|
|
81
|
-
|
135
|
+
now = RobotController.getFPGATime()
|
82
136
|
packetWithTimestamp = self._rawBytesEntry.getAtomic()
|
83
137
|
byteList = packetWithTimestamp.value
|
84
|
-
|
138
|
+
packetWithTimestamp.time
|
85
139
|
|
86
140
|
if len(byteList) < 1:
|
87
|
-
return
|
141
|
+
return PhotonPipelineResult()
|
88
142
|
else:
|
89
143
|
pkt = Packet(byteList)
|
90
|
-
retVal.
|
91
|
-
#
|
92
|
-
retVal.
|
93
|
-
timestamp / 1e6 - retVal.getLatencyMillis() / 1e3
|
94
|
-
)
|
144
|
+
retVal = PhotonPipelineResult.photonStruct.unpack(pkt)
|
145
|
+
# We don't trust NT4 time, hack around
|
146
|
+
retVal.ntReceiveTimestampMicros = now
|
95
147
|
return retVal
|
96
148
|
|
97
149
|
def getDriverMode(self) -> bool:
|
@@ -147,6 +199,16 @@ class PhotonCamera:
|
|
147
199
|
cameraNames = (
|
148
200
|
self._cameraTable.getInstance().getTable(self._tableName).getSubTables()
|
149
201
|
)
|
202
|
+
# Look for only cameras with rawBytes entry that exists
|
203
|
+
cameraNames = list(
|
204
|
+
filter(
|
205
|
+
lambda it: self._cameraTable.getSubTable(it)
|
206
|
+
.getEntry("rawBytes")
|
207
|
+
.exists(),
|
208
|
+
cameraNames,
|
209
|
+
)
|
210
|
+
)
|
211
|
+
|
150
212
|
if len(cameraNames) == 0:
|
151
213
|
wpilib.reportError(
|
152
214
|
"Could not find any PhotonVision coprocessors on NetworkTables. Double check that PhotonVision is running, and that your camera is connected!",
|
@@ -165,7 +227,20 @@ class PhotonCamera:
|
|
165
227
|
)
|
166
228
|
|
167
229
|
versionString = self.versionEntry.get(defaultValue="")
|
168
|
-
|
230
|
+
localUUID = PhotonPipelineResult.photonStruct.MESSAGE_VERSION
|
231
|
+
|
232
|
+
remoteUUID = self._rawBytesEntry.getTopic().getProperty("message_uuid")
|
233
|
+
|
234
|
+
if remoteUUID is None or len(remoteUUID) == 0:
|
235
|
+
wpilib.reportWarning(
|
236
|
+
f"PhotonVision coprocessor at path {self._path} has not reported a message interface UUID - is your coprocessor's camera started?",
|
237
|
+
True,
|
238
|
+
)
|
239
|
+
|
240
|
+
# ntcore hands us a JSON string with leading/trailing quotes - remove those
|
241
|
+
remoteUUID = remoteUUID.replace('"', "")
|
242
|
+
|
243
|
+
if localUUID != remoteUUID:
|
169
244
|
# Verified version mismatch
|
170
245
|
|
171
246
|
bfw = """
|
@@ -190,6 +265,6 @@ class PhotonCamera:
|
|
190
265
|
|
191
266
|
wpilib.reportWarning(bfw)
|
192
267
|
|
193
|
-
errText = f"
|
268
|
+
errText = f"Photonlibpy version {PHOTONLIB_VERSION} (With message UUID {localUUID}) does not match coprocessor version {versionString} (with message UUID {remoteUUID}). Please install photonlibpy version {versionString}, or update your coprocessor to {PHOTONLIB_VERSION}."
|
194
269
|
wpilib.reportError(errText, True)
|
195
270
|
raise Exception(errText)
|
@@ -1,3 +1,20 @@
|
|
1
|
+
###############################################################################
|
2
|
+
## Copyright (C) Photon Vision.
|
3
|
+
###############################################################################
|
4
|
+
## This program is free software: you can redistribute it and/or modify
|
5
|
+
## it under the terms of the GNU General Public License as published by
|
6
|
+
## the Free Software Foundation, either version 3 of the License, or
|
7
|
+
## (at your option) any later version.
|
8
|
+
##
|
9
|
+
## This program is distributed in the hope that it will be useful,
|
10
|
+
## but WITHOUT ANY WARRANTY; without even the implied warranty of
|
11
|
+
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
12
|
+
## GNU General Public License for more details.
|
13
|
+
##
|
14
|
+
## You should have received a copy of the GNU General Public License
|
15
|
+
## along with this program. If not, see <https://www.gnu.org/licenses/>.
|
16
|
+
###############################################################################
|
17
|
+
|
1
18
|
import enum
|
2
19
|
from typing import Optional
|
3
20
|
|
@@ -5,7 +22,7 @@ import wpilib
|
|
5
22
|
from robotpy_apriltag import AprilTagFieldLayout
|
6
23
|
from wpimath.geometry import Transform3d, Pose3d, Pose2d
|
7
24
|
|
8
|
-
from .photonPipelineResult import PhotonPipelineResult
|
25
|
+
from .targeting.photonPipelineResult import PhotonPipelineResult
|
9
26
|
from .photonCamera import PhotonCamera
|
10
27
|
from .estimatedRobotPose import EstimatedRobotPose
|
11
28
|
|
@@ -207,7 +224,7 @@ class PhotonPoseEstimator:
|
|
207
224
|
return None
|
208
225
|
cameraResult = self._camera.getLatestResult()
|
209
226
|
|
210
|
-
if cameraResult.
|
227
|
+
if cameraResult.getTimestampSeconds() < 0:
|
211
228
|
return None
|
212
229
|
|
213
230
|
# If the pose cache timestamp was set, and the result is from the same
|
@@ -215,12 +232,15 @@ class PhotonPoseEstimator:
|
|
215
232
|
# empty result
|
216
233
|
if (
|
217
234
|
self._poseCacheTimestampSeconds > 0.0
|
218
|
-
and abs(
|
235
|
+
and abs(
|
236
|
+
self._poseCacheTimestampSeconds - cameraResult.getTimestampSeconds()
|
237
|
+
)
|
238
|
+
< 1e-6
|
219
239
|
):
|
220
240
|
return None
|
221
241
|
|
222
242
|
# Remember the timestamp of the current result used
|
223
|
-
self._poseCacheTimestampSeconds = cameraResult.
|
243
|
+
self._poseCacheTimestampSeconds = cameraResult.getTimestampSeconds()
|
224
244
|
|
225
245
|
# If no targets seen, trivial case -- return empty result
|
226
246
|
if not cameraResult.targets:
|
@@ -259,7 +279,7 @@ class PhotonPoseEstimator:
|
|
259
279
|
)
|
260
280
|
return EstimatedRobotPose(
|
261
281
|
best,
|
262
|
-
result.
|
282
|
+
result.getTimestampSeconds(),
|
263
283
|
result.targets,
|
264
284
|
PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR,
|
265
285
|
)
|
@@ -281,7 +301,6 @@ class PhotonPoseEstimator:
|
|
281
301
|
lowestAmbiguityTarget = None
|
282
302
|
|
283
303
|
lowestAmbiguityScore = 10.0
|
284
|
-
|
285
304
|
for target in result.targets:
|
286
305
|
targetPoseAmbiguity = target.poseAmbiguity
|
287
306
|
|
@@ -307,7 +326,7 @@ class PhotonPoseEstimator:
|
|
307
326
|
targetPosition.transformBy(
|
308
327
|
lowestAmbiguityTarget.getBestCameraToTarget().inverse()
|
309
328
|
).transformBy(self.robotToCamera.inverse()),
|
310
|
-
result.
|
329
|
+
result.getTimestampSeconds(),
|
311
330
|
result.targets,
|
312
331
|
PoseStrategy.LOWEST_AMBIGUITY,
|
313
332
|
)
|
@@ -0,0 +1,6 @@
|
|
1
|
+
# no one but us chickens
|
2
|
+
|
3
|
+
from .TargetCorner import TargetCorner # noqa
|
4
|
+
from .multiTargetPNPResult import MultiTargetPNPResult, PnpResult # noqa
|
5
|
+
from .photonPipelineResult import PhotonPipelineMetadata, PhotonPipelineResult # noqa
|
6
|
+
from .photonTrackedTarget import PhotonTrackedTarget # noqa
|
@@ -0,0 +1,34 @@
|
|
1
|
+
from dataclasses import dataclass, field
|
2
|
+
from wpimath.geometry import Transform3d
|
3
|
+
from ..packet import Packet
|
4
|
+
|
5
|
+
|
6
|
+
@dataclass
|
7
|
+
class PnpResult:
|
8
|
+
best: Transform3d = field(default_factory=Transform3d)
|
9
|
+
alt: Transform3d = field(default_factory=Transform3d)
|
10
|
+
ambiguity: float = 0.0
|
11
|
+
bestReprojError: float = 0.0
|
12
|
+
altReprojError: float = 0.0
|
13
|
+
|
14
|
+
photonStruct: "PNPResultSerde" = None
|
15
|
+
|
16
|
+
|
17
|
+
@dataclass
|
18
|
+
class MultiTargetPNPResult:
|
19
|
+
_MAX_IDS = 32
|
20
|
+
|
21
|
+
estimatedPose: PnpResult = field(default_factory=PnpResult)
|
22
|
+
fiducialIDsUsed: list[int] = field(default_factory=list)
|
23
|
+
|
24
|
+
def createFromPacket(self, packet: Packet) -> Packet:
|
25
|
+
self.estimatedPose = PnpResult()
|
26
|
+
self.estimatedPose.createFromPacket(packet)
|
27
|
+
self.fiducialIDsUsed = []
|
28
|
+
for _ in range(MultiTargetPNPResult._MAX_IDS):
|
29
|
+
fidId = packet.decode16()
|
30
|
+
if fidId >= 0:
|
31
|
+
self.fiducialIDsUsed.append(fidId)
|
32
|
+
return packet
|
33
|
+
|
34
|
+
photonStruct: "MultiTargetPNPResultSerde" = None
|
@@ -0,0 +1,65 @@
|
|
1
|
+
from dataclasses import dataclass, field
|
2
|
+
from typing import Optional
|
3
|
+
|
4
|
+
from .multiTargetPNPResult import MultiTargetPNPResult
|
5
|
+
from .photonTrackedTarget import PhotonTrackedTarget
|
6
|
+
|
7
|
+
|
8
|
+
@dataclass
|
9
|
+
class PhotonPipelineMetadata:
|
10
|
+
# Image capture and NT publish timestamp, in microseconds and in the coprocessor timebase. As
|
11
|
+
# reported by WPIUtilJNI::now.
|
12
|
+
captureTimestampMicros: int = -1
|
13
|
+
publishTimestampMicros: int = -1
|
14
|
+
|
15
|
+
# Mirror of the heartbeat entry -- monotonically increasing
|
16
|
+
sequenceID: int = -1
|
17
|
+
|
18
|
+
photonStruct: "PhotonPipelineMetadataSerde" = None
|
19
|
+
|
20
|
+
|
21
|
+
@dataclass
|
22
|
+
class PhotonPipelineResult:
|
23
|
+
# Since we don't trust NT time sync, keep track of when we got this packet into robot code
|
24
|
+
ntReceiveTimestampMicros: int = -1
|
25
|
+
|
26
|
+
targets: list[PhotonTrackedTarget] = field(default_factory=list)
|
27
|
+
metadata: PhotonPipelineMetadata = field(default_factory=PhotonPipelineMetadata)
|
28
|
+
multiTagResult: Optional[MultiTargetPNPResult] = None
|
29
|
+
|
30
|
+
def getLatencyMillis(self) -> float:
|
31
|
+
return (
|
32
|
+
self.metadata.publishTimestampMicros - self.metadata.captureTimestampMicros
|
33
|
+
) / 1e3
|
34
|
+
|
35
|
+
def getTimestampSeconds(self) -> float:
|
36
|
+
"""
|
37
|
+
Returns the estimated time the frame was taken, in the Received system's time base. This is
|
38
|
+
calculated as (NT Receive time (robot base) - (publish timestamp, coproc timebase - capture
|
39
|
+
timestamp, coproc timebase))
|
40
|
+
"""
|
41
|
+
# TODO - we don't trust NT4 to correctly latency-compensate ntReceiveTimestampMicros
|
42
|
+
return (
|
43
|
+
self.ntReceiveTimestampMicros
|
44
|
+
- (
|
45
|
+
self.metadata.publishTimestampMicros
|
46
|
+
- self.metadata.captureTimestampMicros
|
47
|
+
)
|
48
|
+
) / 1e6
|
49
|
+
|
50
|
+
def getTargets(self) -> list[PhotonTrackedTarget]:
|
51
|
+
return self.targets
|
52
|
+
|
53
|
+
def hasTargets(self) -> bool:
|
54
|
+
return len(self.targets) > 0
|
55
|
+
|
56
|
+
def getBestTarget(self) -> PhotonTrackedTarget:
|
57
|
+
"""
|
58
|
+
Returns the best target in this pipeline result. If there are no targets, this method will
|
59
|
+
return null. The best target is determined by the target sort mode in the PhotonVision UI.
|
60
|
+
"""
|
61
|
+
if not self.hasTargets():
|
62
|
+
return None
|
63
|
+
return self.getTargets()[0]
|
64
|
+
|
65
|
+
photonStruct: "PhotonPipelineResultSerde" = None
|
@@ -1,20 +1,11 @@
|
|
1
1
|
from dataclasses import dataclass, field
|
2
2
|
from wpimath.geometry import Transform3d
|
3
|
-
from
|
4
|
-
|
5
|
-
|
6
|
-
@dataclass
|
7
|
-
class TargetCorner:
|
8
|
-
x: float
|
9
|
-
y: float
|
3
|
+
from ..packet import Packet
|
4
|
+
from .TargetCorner import TargetCorner
|
10
5
|
|
11
6
|
|
12
7
|
@dataclass
|
13
8
|
class PhotonTrackedTarget:
|
14
|
-
_MAX_CORNERS = 8
|
15
|
-
_NUM_BYTES_IN_FLOAT = 8
|
16
|
-
_PACK_SIZE_BYTES = _NUM_BYTES_IN_FLOAT * (5 + 7 + 2 * 4 + 1 + 7 + 2 * _MAX_CORNERS)
|
17
|
-
|
18
9
|
yaw: float = 0.0
|
19
10
|
pitch: float = 0.0
|
20
11
|
area: float = 0.0
|
@@ -64,19 +55,4 @@ class PhotonTrackedTarget:
|
|
64
55
|
retList.append(TargetCorner(cx, cy))
|
65
56
|
return retList
|
66
57
|
|
67
|
-
|
68
|
-
self.yaw = packet.decodeDouble()
|
69
|
-
self.pitch = packet.decodeDouble()
|
70
|
-
self.area = packet.decodeDouble()
|
71
|
-
self.skew = packet.decodeDouble()
|
72
|
-
self.fiducialId = packet.decode32()
|
73
|
-
|
74
|
-
self.bestCameraToTarget = packet.decodeTransform()
|
75
|
-
self.altCameraToTarget = packet.decodeTransform()
|
76
|
-
|
77
|
-
self.poseAmbiguity = packet.decodeDouble()
|
78
|
-
|
79
|
-
self.minAreaRectCorners = self._decodeTargetList(packet, 4) # always four
|
80
|
-
numCorners = packet.decode8()
|
81
|
-
self.detectedCorners = self._decodeTargetList(packet, numCorners)
|
82
|
-
return packet
|
58
|
+
photonStruct: "PhotonTrackedTargetSerde" = None
|
photonlibpy/version.py
CHANGED
@@ -1,2 +1,2 @@
|
|
1
|
-
PHOTONLIB_VERSION="
|
2
|
-
PHOTONVISION_VERSION="
|
1
|
+
PHOTONLIB_VERSION="v2025.0.0.alpha.0"
|
2
|
+
PHOTONVISION_VERSION="v2025.0.0-alpha-0"
|
@@ -0,0 +1,13 @@
|
|
1
|
+
Metadata-Version: 2.1
|
2
|
+
Name: photonlibpy
|
3
|
+
Version: 2025.0.0a0
|
4
|
+
Summary: Pure-python implementation of PhotonLib for interfacing with PhotonVision on coprocessors. Implemented with PhotonVision version v2025.0.0-alpha-0 .
|
5
|
+
Home-page: https://photonvision.org
|
6
|
+
Author: Photonvision Development Team
|
7
|
+
Description-Content-Type: text/markdown
|
8
|
+
Requires-Dist: wpilib<2025,>=2024.0.0b2
|
9
|
+
Requires-Dist: robotpy-wpimath<2025,>=2024.0.0b2
|
10
|
+
Requires-Dist: robotpy-apriltag<2025,>=2024.0.0b2
|
11
|
+
Requires-Dist: pyntcore<2025,>=2024.0.0b2
|
12
|
+
|
13
|
+
A Pure-python implementation of PhotonLib
|
@@ -0,0 +1,22 @@
|
|
1
|
+
photonlibpy/__init__.py,sha256=JnwWj53fEM263hUjEFGmJ--M3XCX0LYovdrl4wcNRnU,1136
|
2
|
+
photonlibpy/estimatedRobotPose.py,sha256=X7wF9xdPXGKSVy0MY0qrWZJOEbuZPd721lYp0KXKlP0,1603
|
3
|
+
photonlibpy/packet.py,sha256=gcikxwQZLoNGHuzNpAmnXjyLty-8w8HIVR3gGl4QPX4,6024
|
4
|
+
photonlibpy/photonCamera.py,sha256=nc80dRGm_4OT_EcJo9zmmCaiDY3FMmAgYoYDrTCKEfk,10187
|
5
|
+
photonlibpy/photonPoseEstimator.py,sha256=cgTW2Ja9cJK08bIKd-zW0l1V8mLL5NM_unaIOgEsedk,12596
|
6
|
+
photonlibpy/version.py,sha256=Fg2UjgOnC98Q0vrMlyrceRwAyQMW9fCGWswIYeblBQY,79
|
7
|
+
photonlibpy/generated/MultiTargetPNPResultSerde.py,sha256=vtcg17D83gVtXJBCAez8xFmxdENV020QcY4gfYZOBd4,1957
|
8
|
+
photonlibpy/generated/PhotonPipelineMetadataSerde.py,sha256=eXLgqVQfaK7nPLeu832Z2RsH3BfffGPDCXvw0DCvjTw,2081
|
9
|
+
photonlibpy/generated/PhotonPipelineResultSerde.py,sha256=jPq9C1895UO1fbipuO9V6TPrFZ5IOVbTNzctnlTjRBQ,2261
|
10
|
+
photonlibpy/generated/PhotonTrackedTargetSerde.py,sha256=v_VFmq8h6KIarAdmqsV1DLClF3mQUVJzRbk-DLDwjU4,3070
|
11
|
+
photonlibpy/generated/PnpResultSerde.py,sha256=LqQ2-25ac8o8BoV24UL0gkG4cQ6KrZNbajNZngYjSI4,2080
|
12
|
+
photonlibpy/generated/TargetCornerSerde.py,sha256=ehkIitRVneMppqnEn3XPn_giUNH-czT3O_YID5fxdos,1790
|
13
|
+
photonlibpy/generated/__init__.py,sha256=WdCA9k7QNY1i8B9u5kBilnibajDBg7zfU8GbV7F2H8g,505
|
14
|
+
photonlibpy/targeting/TargetCorner.py,sha256=iFWTWu5HcpkBQyvhz_klpAB0TEmy-7_SsD1FHeNfnkE,147
|
15
|
+
photonlibpy/targeting/__init__.py,sha256=1GUy4MC8NbZ-TEcFgsnvSm_X0LYeZ0HZagMMRmGpx8A,295
|
16
|
+
photonlibpy/targeting/multiTargetPNPResult.py,sha256=CZ7jULJV1VpTK5mxLvMVKHkBMKdTk9X428cNChzizAY,1010
|
17
|
+
photonlibpy/targeting/photonPipelineResult.py,sha256=t3fHHEb6YgucJyTajCi3-SIG9FSQGQ4sUQLadFfhIks,2316
|
18
|
+
photonlibpy/targeting/photonTrackedTarget.py,sha256=B1kMfx6Re0VF_RsMZ7H0ZyxaGy4PR4XITiaCbe0ViZ0,1708
|
19
|
+
photonlibpy-2025.0.0a0.dist-info/METADATA,sha256=zZc6rK9qOYvIQGeXfoCx6qorsNoMaYn2YKdcBMrib48,556
|
20
|
+
photonlibpy-2025.0.0a0.dist-info/WHEEL,sha256=eOLhNAGa2EW3wWl_TU484h7q1UNgy0JXjjoqKoxAAQc,92
|
21
|
+
photonlibpy-2025.0.0a0.dist-info/top_level.txt,sha256=T8Xc6U6he2VjKUAca6zawSkHdUZuLanxYIc4nxw2ctc,12
|
22
|
+
photonlibpy-2025.0.0a0.dist-info/RECORD,,
|
@@ -1,49 +0,0 @@
|
|
1
|
-
from dataclasses import dataclass, field
|
2
|
-
from wpimath.geometry import Transform3d
|
3
|
-
from photonlibpy.packet import Packet
|
4
|
-
|
5
|
-
|
6
|
-
@dataclass
|
7
|
-
class PNPResult:
|
8
|
-
_NUM_BYTES_IN_FLOAT = 8
|
9
|
-
PACK_SIZE_BYTES = 1 + (_NUM_BYTES_IN_FLOAT * 7 * 2) + (_NUM_BYTES_IN_FLOAT * 3)
|
10
|
-
|
11
|
-
isPresent: bool = False
|
12
|
-
best: Transform3d = field(default_factory=Transform3d)
|
13
|
-
alt: Transform3d = field(default_factory=Transform3d)
|
14
|
-
ambiguity: float = 0.0
|
15
|
-
bestReprojError: float = 0.0
|
16
|
-
altReprojError: float = 0.0
|
17
|
-
|
18
|
-
def createFromPacket(self, packet: Packet) -> Packet:
|
19
|
-
self.isPresent = packet.decodeBoolean()
|
20
|
-
|
21
|
-
if not self.isPresent:
|
22
|
-
return packet
|
23
|
-
|
24
|
-
self.best = packet.decodeTransform()
|
25
|
-
self.alt = packet.decodeTransform()
|
26
|
-
self.bestReprojError = packet.decodeDouble()
|
27
|
-
self.altReprojError = packet.decodeDouble()
|
28
|
-
self.ambiguity = packet.decodeDouble()
|
29
|
-
return packet
|
30
|
-
|
31
|
-
|
32
|
-
@dataclass
|
33
|
-
class MultiTargetPNPResult:
|
34
|
-
_MAX_IDS = 32
|
35
|
-
# pnpresult + MAX_IDS possible targets (arbitrary upper limit that should never be hit, ideally)
|
36
|
-
_PACK_SIZE_BYTES = PNPResult.PACK_SIZE_BYTES + (1 * _MAX_IDS)
|
37
|
-
|
38
|
-
estimatedPose: PNPResult = field(default_factory=PNPResult)
|
39
|
-
fiducialIDsUsed: list[int] = field(default_factory=list)
|
40
|
-
|
41
|
-
def createFromPacket(self, packet: Packet) -> Packet:
|
42
|
-
self.estimatedPose = PNPResult()
|
43
|
-
self.estimatedPose.createFromPacket(packet)
|
44
|
-
self.fiducialIDsUsed = []
|
45
|
-
for _ in range(MultiTargetPNPResult._MAX_IDS):
|
46
|
-
fidId = packet.decode16()
|
47
|
-
if fidId >= 0:
|
48
|
-
self.fiducialIDsUsed.append(fidId)
|
49
|
-
return packet
|
@@ -1,43 +0,0 @@
|
|
1
|
-
from dataclasses import dataclass, field
|
2
|
-
|
3
|
-
from photonlibpy.multiTargetPNPResult import MultiTargetPNPResult
|
4
|
-
from photonlibpy.packet import Packet
|
5
|
-
from photonlibpy.photonTrackedTarget import PhotonTrackedTarget
|
6
|
-
|
7
|
-
|
8
|
-
@dataclass
|
9
|
-
class PhotonPipelineResult:
|
10
|
-
latencyMillis: float = -1.0
|
11
|
-
timestampSec: float = -1.0
|
12
|
-
targets: list[PhotonTrackedTarget] = field(default_factory=list)
|
13
|
-
multiTagResult: MultiTargetPNPResult = field(default_factory=MultiTargetPNPResult)
|
14
|
-
|
15
|
-
def populateFromPacket(self, packet: Packet) -> Packet:
|
16
|
-
self.targets = []
|
17
|
-
self.latencyMillis = packet.decodeDouble()
|
18
|
-
targetCount = packet.decode8()
|
19
|
-
|
20
|
-
for _ in range(targetCount):
|
21
|
-
target = PhotonTrackedTarget()
|
22
|
-
target.createFromPacket(packet)
|
23
|
-
self.targets.append(target)
|
24
|
-
|
25
|
-
self.multiTagResult = MultiTargetPNPResult()
|
26
|
-
self.multiTagResult.createFromPacket(packet)
|
27
|
-
|
28
|
-
return packet
|
29
|
-
|
30
|
-
def setTimestampSeconds(self, timestampSec: float) -> None:
|
31
|
-
self.timestampSec = timestampSec
|
32
|
-
|
33
|
-
def getLatencyMillis(self) -> float:
|
34
|
-
return self.latencyMillis
|
35
|
-
|
36
|
-
def getTimestamp(self) -> float:
|
37
|
-
return self.timestampSec
|
38
|
-
|
39
|
-
def getTargets(self) -> list[PhotonTrackedTarget]:
|
40
|
-
return self.targets
|
41
|
-
|
42
|
-
def hasTargets(self) -> bool:
|
43
|
-
return len(self.targets) > 0
|
@@ -1,13 +0,0 @@
|
|
1
|
-
Metadata-Version: 2.1
|
2
|
-
Name: photonlibpy
|
3
|
-
Version: 2024.3.1
|
4
|
-
Summary: Pure-python implementation of PhotonLib for interfacing with PhotonVision on coprocessors.
|
5
|
-
Home-page: https://photonvision.org
|
6
|
-
Author: Photonvision Development Team
|
7
|
-
Description-Content-Type: text/markdown
|
8
|
-
Requires-Dist: wpilib <2025,>=2024.0.0b2
|
9
|
-
Requires-Dist: robotpy-wpimath <2025,>=2024.0.0b2
|
10
|
-
Requires-Dist: robotpy-apriltag <2025,>=2024.0.0b2
|
11
|
-
Requires-Dist: pyntcore <2025,>=2024.0.0b2
|
12
|
-
|
13
|
-
A Pure-python implementation of PhotonLib
|
@@ -1,13 +0,0 @@
|
|
1
|
-
photonlibpy/__init__.py,sha256=Poafj5ngdQ2T0yW3zhnQ2NHw70XrTwXvT8aDCAImYbg,30
|
2
|
-
photonlibpy/estimatedRobotPose.py,sha256=_lgVu157fBpG85WpeS4uXWCF4aQDUbMI2SWXG5lee9I,673
|
3
|
-
photonlibpy/multiTargetPNPResult.py,sha256=AgrRjSna1s8yJWUdBgWxqKxm0cqgXwYrKEzgfP7pzGE,1660
|
4
|
-
photonlibpy/packet.py,sha256=Sg_Sln_DNYvdT0DpekIb6v67e3c4oX08zLQe9oDd2OU,3969
|
5
|
-
photonlibpy/photonCamera.py,sha256=5bbyMIVnz9oCfeQR0CrycjrM7TuoDF_ybe6OZbAdVpk,6946
|
6
|
-
photonlibpy/photonPipelineResult.py,sha256=IpHxXKuyfOKcslgm_Ce2PqV8HgXTN_IMUuNb5BBTzSo,1351
|
7
|
-
photonlibpy/photonPoseEstimator.py,sha256=s99TjCi3SFpCo5fPckw2ZfJK7E3lvFO3zpr0GnDDyKM,11580
|
8
|
-
photonlibpy/photonTrackedTarget.py,sha256=Br2L4fNNwQP4eUj9eV9I653FOER00JbeHB5SMNTSaHc,2482
|
9
|
-
photonlibpy/version.py,sha256=cLtN559uk-KlzHhdhRQ2MoAO-iHP1C1nyS5PJ2F8TZo,62
|
10
|
-
photonlibpy-2024.3.1.dist-info/METADATA,sha256=hd_3Q0yZnYzxZ4wHBequLJQOJokRlO-sq8zoOcQsvl8,500
|
11
|
-
photonlibpy-2024.3.1.dist-info/WHEEL,sha256=GJ7t_kWBFywbagK5eo9IoUwLW6oyOeTKmQ-9iHFVNxQ,92
|
12
|
-
photonlibpy-2024.3.1.dist-info/top_level.txt,sha256=T8Xc6U6he2VjKUAca6zawSkHdUZuLanxYIc4nxw2ctc,12
|
13
|
-
photonlibpy-2024.3.1.dist-info/RECORD,,
|
File without changes
|