photonlibpy 2025.0.0a0__py3-none-any.whl → 2025.0.0b2__py3-none-any.whl
Sign up to get free protection for your applications and to get access to all the features.
- photonlibpy/__init__.py +2 -2
- photonlibpy/estimation/__init__.py +5 -0
- photonlibpy/estimation/cameraTargetRelation.py +25 -0
- photonlibpy/estimation/openCVHelp.py +200 -0
- photonlibpy/estimation/rotTrlTransform3d.py +32 -0
- photonlibpy/estimation/targetModel.py +137 -0
- photonlibpy/estimation/visionEstimation.py +91 -0
- photonlibpy/generated/MultiTargetPNPResultSerde.py +12 -0
- photonlibpy/generated/PhotonPipelineMetadataSerde.py +23 -4
- photonlibpy/generated/PhotonPipelineResultSerde.py +19 -2
- photonlibpy/generated/PhotonTrackedTargetSerde.py +40 -0
- photonlibpy/generated/PnpResultSerde.py +19 -0
- photonlibpy/generated/TargetCornerSerde.py +12 -0
- photonlibpy/generated/__init__.py +0 -1
- photonlibpy/networktables/NTTopicSet.py +64 -0
- photonlibpy/networktables/__init__.py +1 -0
- photonlibpy/packet.py +123 -8
- photonlibpy/photonCamera.py +10 -7
- photonlibpy/photonPoseEstimator.py +5 -5
- photonlibpy/simulation/__init__.py +5 -0
- photonlibpy/simulation/photonCameraSim.py +408 -0
- photonlibpy/simulation/simCameraProperties.py +661 -0
- photonlibpy/simulation/videoSimUtil.py +2 -0
- photonlibpy/simulation/visionSystemSim.py +237 -0
- photonlibpy/simulation/visionTargetSim.py +50 -0
- photonlibpy/targeting/TargetCorner.py +5 -1
- photonlibpy/targeting/__init__.py +1 -1
- photonlibpy/targeting/multiTargetPNPResult.py +10 -4
- photonlibpy/targeting/photonPipelineResult.py +12 -5
- photonlibpy/targeting/photonTrackedTarget.py +13 -5
- photonlibpy/version.py +2 -2
- {photonlibpy-2025.0.0a0.dist-info → photonlibpy-2025.0.0b2.dist-info}/METADATA +6 -2
- photonlibpy-2025.0.0b2.dist-info/RECORD +36 -0
- {photonlibpy-2025.0.0a0.dist-info → photonlibpy-2025.0.0b2.dist-info}/WHEEL +1 -1
- photonlibpy-2025.0.0a0.dist-info/RECORD +0 -22
- {photonlibpy-2025.0.0a0.dist-info → photonlibpy-2025.0.0b2.dist-info}/top_level.txt +0 -0
@@ -0,0 +1,237 @@
|
|
1
|
+
import typing
|
2
|
+
|
3
|
+
import wpilib
|
4
|
+
from robotpy_apriltag import AprilTagFieldLayout
|
5
|
+
from wpilib import Field2d
|
6
|
+
from wpimath.geometry import Pose2d, Pose3d, Transform3d
|
7
|
+
|
8
|
+
# TODO(auscompgeek): update import path when RobotPy re-exports are fixed
|
9
|
+
from wpimath.interpolation._interpolation import TimeInterpolatablePose3dBuffer
|
10
|
+
from wpimath.units import seconds
|
11
|
+
|
12
|
+
from ..estimation import TargetModel
|
13
|
+
from .photonCameraSim import PhotonCameraSim
|
14
|
+
from .visionTargetSim import VisionTargetSim
|
15
|
+
|
16
|
+
|
17
|
+
class VisionSystemSim:
|
18
|
+
def __init__(self, visionSystemName: str):
|
19
|
+
self.dbgField: Field2d = Field2d()
|
20
|
+
self.bufferLength: seconds = 1.5
|
21
|
+
|
22
|
+
self.camSimMap: typing.Dict[str, PhotonCameraSim] = {}
|
23
|
+
self.camTrfMap: typing.Dict[PhotonCameraSim, TimeInterpolatablePose3dBuffer] = (
|
24
|
+
{}
|
25
|
+
)
|
26
|
+
self.robotPoseBuffer: TimeInterpolatablePose3dBuffer = (
|
27
|
+
TimeInterpolatablePose3dBuffer(self.bufferLength)
|
28
|
+
)
|
29
|
+
self.targetSets: typing.Dict[str, list[VisionTargetSim]] = {}
|
30
|
+
|
31
|
+
self.tableName: str = "VisionSystemSim-" + visionSystemName
|
32
|
+
wpilib.SmartDashboard.putData(self.tableName + "/Sim Field", self.dbgField)
|
33
|
+
|
34
|
+
def getCameraSim(self, name: str) -> PhotonCameraSim | None:
|
35
|
+
return self.camSimMap.get(name, None)
|
36
|
+
|
37
|
+
def getCameraSims(self) -> list[PhotonCameraSim]:
|
38
|
+
return [*self.camSimMap.values()]
|
39
|
+
|
40
|
+
def addCamera(self, cameraSim: PhotonCameraSim, robotToCamera: Transform3d) -> None:
|
41
|
+
name = cameraSim.getCamera().getName()
|
42
|
+
if name not in self.camSimMap:
|
43
|
+
self.camSimMap[name] = cameraSim
|
44
|
+
self.camTrfMap[cameraSim] = TimeInterpolatablePose3dBuffer(
|
45
|
+
self.bufferLength
|
46
|
+
)
|
47
|
+
self.camTrfMap[cameraSim].addSample(
|
48
|
+
wpilib.Timer.getFPGATimestamp(), Pose3d() + robotToCamera
|
49
|
+
)
|
50
|
+
|
51
|
+
def clearCameras(self) -> None:
|
52
|
+
self.camSimMap.clear()
|
53
|
+
self.camTrfMap.clear()
|
54
|
+
|
55
|
+
def removeCamera(self, cameraSim: PhotonCameraSim) -> bool:
|
56
|
+
name = cameraSim.getCamera().getName()
|
57
|
+
if name in self.camSimMap:
|
58
|
+
del self.camSimMap[name]
|
59
|
+
return True
|
60
|
+
else:
|
61
|
+
return False
|
62
|
+
|
63
|
+
def getRobotToCamera(
|
64
|
+
self,
|
65
|
+
cameraSim: PhotonCameraSim,
|
66
|
+
time: seconds = wpilib.Timer.getFPGATimestamp(),
|
67
|
+
) -> Transform3d | None:
|
68
|
+
if cameraSim in self.camTrfMap:
|
69
|
+
trfBuffer = self.camTrfMap[cameraSim]
|
70
|
+
sample = trfBuffer.sample(time)
|
71
|
+
if sample is None:
|
72
|
+
return None
|
73
|
+
else:
|
74
|
+
return Transform3d(Pose3d(), sample)
|
75
|
+
else:
|
76
|
+
return None
|
77
|
+
|
78
|
+
def getCameraPose(
|
79
|
+
self,
|
80
|
+
cameraSim: PhotonCameraSim,
|
81
|
+
time: seconds = wpilib.Timer.getFPGATimestamp(),
|
82
|
+
) -> Pose3d | None:
|
83
|
+
robotToCamera = self.getRobotToCamera(cameraSim, time)
|
84
|
+
if robotToCamera is None:
|
85
|
+
return None
|
86
|
+
else:
|
87
|
+
return self.getRobotPose(time) + robotToCamera
|
88
|
+
|
89
|
+
def adjustCamera(
|
90
|
+
self, cameraSim: PhotonCameraSim, robotToCamera: Transform3d
|
91
|
+
) -> bool:
|
92
|
+
if cameraSim in self.camTrfMap:
|
93
|
+
self.camTrfMap[cameraSim].addSample(
|
94
|
+
wpilib.Timer.getFPGATimestamp(), Pose3d() + robotToCamera
|
95
|
+
)
|
96
|
+
return True
|
97
|
+
else:
|
98
|
+
return False
|
99
|
+
|
100
|
+
def resetCameraTransforms(self, cameraSim: PhotonCameraSim | None = None) -> None:
|
101
|
+
now = wpilib.Timer.getFPGATimestamp()
|
102
|
+
|
103
|
+
def resetSingleCamera(self, cameraSim: PhotonCameraSim) -> bool:
|
104
|
+
if cameraSim in self.camTrfMap:
|
105
|
+
trfBuffer = self.camTrfMap[cameraSim]
|
106
|
+
lastTrf = Transform3d(Pose3d(), trfBuffer.sample(now))
|
107
|
+
trfBuffer.clear()
|
108
|
+
self.adjustCamera(cameraSim, lastTrf)
|
109
|
+
return True
|
110
|
+
else:
|
111
|
+
return False
|
112
|
+
|
113
|
+
if cameraSim is None:
|
114
|
+
for camera in self.camTrfMap.keys():
|
115
|
+
resetSingleCamera(self, camera)
|
116
|
+
else:
|
117
|
+
resetSingleCamera(self, cameraSim)
|
118
|
+
|
119
|
+
def getVisionTargets(self, targetType: str | None = None) -> list[VisionTargetSim]:
|
120
|
+
if targetType is None:
|
121
|
+
all: list[VisionTargetSim] = []
|
122
|
+
for targets in self.targetSets.values():
|
123
|
+
for target in targets:
|
124
|
+
all.append(target)
|
125
|
+
return all
|
126
|
+
else:
|
127
|
+
return self.targetSets[targetType]
|
128
|
+
|
129
|
+
def addVisionTargets(
|
130
|
+
self, targets: list[VisionTargetSim], targetType: str = "targets"
|
131
|
+
) -> None:
|
132
|
+
if targetType not in self.targetSets:
|
133
|
+
self.targetSets[targetType] = targets
|
134
|
+
else:
|
135
|
+
self.targetSets[targetType] += targets
|
136
|
+
|
137
|
+
def addAprilTags(self, layout: AprilTagFieldLayout) -> None:
|
138
|
+
targets: list[VisionTargetSim] = []
|
139
|
+
for tag in layout.getTags():
|
140
|
+
tag_pose = layout.getTagPose(tag.ID)
|
141
|
+
# TODO this was done to make the python gods happy. Confirm that this is desired or if types dont matter
|
142
|
+
assert tag_pose is not None
|
143
|
+
targets.append(
|
144
|
+
VisionTargetSim(tag_pose, TargetModel.AprilTag36h11(), tag.ID)
|
145
|
+
)
|
146
|
+
self.addVisionTargets(targets, "apriltag")
|
147
|
+
|
148
|
+
def clearVisionTargets(self) -> None:
|
149
|
+
self.targetSets.clear()
|
150
|
+
|
151
|
+
def clearAprilTags(self) -> None:
|
152
|
+
self.removeVisionTargetType("apriltag")
|
153
|
+
|
154
|
+
def removeVisionTargetType(self, targetType: str) -> None:
|
155
|
+
del self.targetSets[targetType]
|
156
|
+
|
157
|
+
def removeVisionTargets(
|
158
|
+
self, targets: list[VisionTargetSim]
|
159
|
+
) -> list[VisionTargetSim]:
|
160
|
+
removedList: list[VisionTargetSim] = []
|
161
|
+
for target in targets:
|
162
|
+
for _, currentTargets in self.targetSets.items():
|
163
|
+
if target in currentTargets:
|
164
|
+
removedList.append(target)
|
165
|
+
currentTargets.remove(target)
|
166
|
+
return removedList
|
167
|
+
|
168
|
+
def getRobotPose(
|
169
|
+
self, timestamp: seconds = wpilib.Timer.getFPGATimestamp()
|
170
|
+
) -> Pose3d:
|
171
|
+
return self.robotPoseBuffer.sample(timestamp)
|
172
|
+
|
173
|
+
def resetRobotPose(self, robotPose: Pose2d | Pose3d) -> None:
|
174
|
+
if type(robotPose) is Pose2d:
|
175
|
+
robotPose = Pose3d(robotPose)
|
176
|
+
assert type(robotPose) is Pose3d
|
177
|
+
|
178
|
+
self.robotPoseBuffer.clear()
|
179
|
+
self.robotPoseBuffer.addSample(wpilib.Timer.getFPGATimestamp(), robotPose)
|
180
|
+
|
181
|
+
def getDebugField(self) -> Field2d:
|
182
|
+
return self.dbgField
|
183
|
+
|
184
|
+
def update(self, robotPose: Pose2d | Pose3d) -> None:
|
185
|
+
if type(robotPose) is Pose2d:
|
186
|
+
robotPose = Pose3d(robotPose)
|
187
|
+
assert type(robotPose) is Pose3d
|
188
|
+
|
189
|
+
for targetType, targets in self.targetSets.items():
|
190
|
+
posesToAdd: list[Pose2d] = []
|
191
|
+
for target in targets:
|
192
|
+
posesToAdd.append(target.getPose().toPose2d())
|
193
|
+
self.dbgField.getObject(targetType).setPoses(posesToAdd)
|
194
|
+
|
195
|
+
now = wpilib.Timer.getFPGATimestamp()
|
196
|
+
self.robotPoseBuffer.addSample(now, robotPose)
|
197
|
+
self.dbgField.setRobotPose(robotPose.toPose2d())
|
198
|
+
|
199
|
+
allTargets: list[VisionTargetSim] = []
|
200
|
+
for targets in self.targetSets.values():
|
201
|
+
for target in targets:
|
202
|
+
allTargets.append(target)
|
203
|
+
|
204
|
+
visTgtPoses2d: list[Pose2d] = []
|
205
|
+
cameraPoses2d: list[Pose2d] = []
|
206
|
+
processed = False
|
207
|
+
for camSim in self.camSimMap.values():
|
208
|
+
optTimestamp = camSim.consumeNextEntryTime()
|
209
|
+
if optTimestamp is None:
|
210
|
+
continue
|
211
|
+
else:
|
212
|
+
processed = True
|
213
|
+
|
214
|
+
timestampNt = optTimestamp
|
215
|
+
latency = camSim.prop.estLatency()
|
216
|
+
timestampCapture = timestampNt * 1.0e-6 - latency
|
217
|
+
|
218
|
+
lateRobotPose = self.getRobotPose(timestampCapture)
|
219
|
+
lateCameraPose = lateRobotPose + self.getRobotToCamera(
|
220
|
+
camSim, timestampCapture
|
221
|
+
)
|
222
|
+
cameraPoses2d.append(lateCameraPose.toPose2d())
|
223
|
+
|
224
|
+
camResult = camSim.process(latency, lateCameraPose, allTargets)
|
225
|
+
camSim.submitProcessedFrame(camResult, timestampNt)
|
226
|
+
for target in camResult.getTargets():
|
227
|
+
trf = target.getBestCameraToTarget()
|
228
|
+
if trf == Transform3d():
|
229
|
+
continue
|
230
|
+
|
231
|
+
visTgtPoses2d.append(lateCameraPose.transformBy(trf).toPose2d())
|
232
|
+
|
233
|
+
if processed:
|
234
|
+
self.dbgField.getObject("visibleTargetPoses").setPoses(visTgtPoses2d)
|
235
|
+
|
236
|
+
if len(cameraPoses2d) != 0:
|
237
|
+
self.dbgField.getObject("cameras").setPoses(cameraPoses2d)
|
@@ -0,0 +1,50 @@
|
|
1
|
+
import math
|
2
|
+
|
3
|
+
from wpimath.geometry import Pose3d, Translation3d
|
4
|
+
|
5
|
+
from ..estimation.targetModel import TargetModel
|
6
|
+
|
7
|
+
|
8
|
+
class VisionTargetSim:
|
9
|
+
def __init__(self, pose: Pose3d, model: TargetModel, id: int = -1):
|
10
|
+
self.pose: Pose3d = pose
|
11
|
+
self.model: TargetModel = model
|
12
|
+
self.fiducialId: int = id
|
13
|
+
self.objDetClassId: int = -1
|
14
|
+
self.objDetConf: float = -1.0
|
15
|
+
|
16
|
+
def __lt__(self, right) -> bool:
|
17
|
+
return self.pose.translation().norm() < right.pose.translation().norm()
|
18
|
+
|
19
|
+
def __eq__(self, other) -> bool:
|
20
|
+
# Use 1 inch and 1 degree tolerance
|
21
|
+
return (
|
22
|
+
abs(self.pose.translation().X() - other.getPose().translation().X())
|
23
|
+
< 0.0254
|
24
|
+
and abs(self.pose.translation().Y() - other.getPose().translation().Y())
|
25
|
+
< 0.0254
|
26
|
+
and abs(self.pose.translation().Z() - other.getPose().translation().Z())
|
27
|
+
< 0.0254
|
28
|
+
and abs(self.pose.rotation().X() - other.getPose().rotation().X())
|
29
|
+
< math.radians(1)
|
30
|
+
and abs(self.pose.rotation().Y() - other.getPose().rotation().Y())
|
31
|
+
< math.radians(1)
|
32
|
+
and abs(self.pose.rotation().Z() - other.getPose().rotation().Z())
|
33
|
+
< math.radians(1)
|
34
|
+
and self.model.getIsPlanar() == other.getModel().getIsPlanar()
|
35
|
+
)
|
36
|
+
|
37
|
+
def setPose(self, newPose: Pose3d) -> None:
|
38
|
+
self.pose = newPose
|
39
|
+
|
40
|
+
def setModel(self, newModel: TargetModel) -> None:
|
41
|
+
self.model = newModel
|
42
|
+
|
43
|
+
def getPose(self) -> Pose3d:
|
44
|
+
return self.pose
|
45
|
+
|
46
|
+
def getModel(self) -> TargetModel:
|
47
|
+
return self.model
|
48
|
+
|
49
|
+
def getFieldVertices(self) -> list[Translation3d]:
|
50
|
+
return self.model.getFieldVertices(self.pose)
|
@@ -1,4 +1,8 @@
|
|
1
1
|
from dataclasses import dataclass
|
2
|
+
from typing import TYPE_CHECKING, ClassVar
|
3
|
+
|
4
|
+
if TYPE_CHECKING:
|
5
|
+
from .. import generated
|
2
6
|
|
3
7
|
|
4
8
|
@dataclass
|
@@ -6,4 +10,4 @@ class TargetCorner:
|
|
6
10
|
x: float = 0
|
7
11
|
y: float = 9
|
8
12
|
|
9
|
-
photonStruct: "TargetCornerSerde"
|
13
|
+
photonStruct: ClassVar["generated.TargetCornerSerde"]
|
@@ -1,6 +1,6 @@
|
|
1
1
|
# no one but us chickens
|
2
2
|
|
3
|
-
from .TargetCorner import TargetCorner # noqa
|
4
3
|
from .multiTargetPNPResult import MultiTargetPNPResult, PnpResult # noqa
|
5
4
|
from .photonPipelineResult import PhotonPipelineMetadata, PhotonPipelineResult # noqa
|
6
5
|
from .photonTrackedTarget import PhotonTrackedTarget # noqa
|
6
|
+
from .TargetCorner import TargetCorner # noqa
|
@@ -1,17 +1,23 @@
|
|
1
1
|
from dataclasses import dataclass, field
|
2
|
+
from typing import TYPE_CHECKING, ClassVar
|
3
|
+
|
2
4
|
from wpimath.geometry import Transform3d
|
5
|
+
|
3
6
|
from ..packet import Packet
|
4
7
|
|
8
|
+
if TYPE_CHECKING:
|
9
|
+
from .. import generated
|
10
|
+
|
5
11
|
|
6
12
|
@dataclass
|
7
13
|
class PnpResult:
|
8
14
|
best: Transform3d = field(default_factory=Transform3d)
|
9
15
|
alt: Transform3d = field(default_factory=Transform3d)
|
10
16
|
ambiguity: float = 0.0
|
11
|
-
|
12
|
-
|
17
|
+
bestReprojErr: float = 0.0
|
18
|
+
altReprojErr: float = 0.0
|
13
19
|
|
14
|
-
photonStruct: "
|
20
|
+
photonStruct: ClassVar["generated.PnpResultSerde"]
|
15
21
|
|
16
22
|
|
17
23
|
@dataclass
|
@@ -31,4 +37,4 @@ class MultiTargetPNPResult:
|
|
31
37
|
self.fiducialIDsUsed.append(fidId)
|
32
38
|
return packet
|
33
39
|
|
34
|
-
photonStruct: "MultiTargetPNPResultSerde"
|
40
|
+
photonStruct: ClassVar["generated.MultiTargetPNPResultSerde"]
|
@@ -1,9 +1,12 @@
|
|
1
1
|
from dataclasses import dataclass, field
|
2
|
-
from typing import Optional
|
2
|
+
from typing import TYPE_CHECKING, ClassVar, Optional
|
3
3
|
|
4
4
|
from .multiTargetPNPResult import MultiTargetPNPResult
|
5
5
|
from .photonTrackedTarget import PhotonTrackedTarget
|
6
6
|
|
7
|
+
if TYPE_CHECKING:
|
8
|
+
from .. import generated
|
9
|
+
|
7
10
|
|
8
11
|
@dataclass
|
9
12
|
class PhotonPipelineMetadata:
|
@@ -15,7 +18,9 @@ class PhotonPipelineMetadata:
|
|
15
18
|
# Mirror of the heartbeat entry -- monotonically increasing
|
16
19
|
sequenceID: int = -1
|
17
20
|
|
18
|
-
|
21
|
+
timeSinceLastPong: int = -1
|
22
|
+
|
23
|
+
photonStruct: ClassVar["generated.PhotonPipelineMetadataSerde"]
|
19
24
|
|
20
25
|
|
21
26
|
@dataclass
|
@@ -24,8 +29,10 @@ class PhotonPipelineResult:
|
|
24
29
|
ntReceiveTimestampMicros: int = -1
|
25
30
|
|
26
31
|
targets: list[PhotonTrackedTarget] = field(default_factory=list)
|
32
|
+
# Python users beware! We don't currently run a Time Sync Server, so these timestamps are in
|
33
|
+
# an arbitrary timebase. This is not true in C++ or Java.
|
27
34
|
metadata: PhotonPipelineMetadata = field(default_factory=PhotonPipelineMetadata)
|
28
|
-
|
35
|
+
multitagResult: Optional[MultiTargetPNPResult] = None
|
29
36
|
|
30
37
|
def getLatencyMillis(self) -> float:
|
31
38
|
return (
|
@@ -53,7 +60,7 @@ class PhotonPipelineResult:
|
|
53
60
|
def hasTargets(self) -> bool:
|
54
61
|
return len(self.targets) > 0
|
55
62
|
|
56
|
-
def getBestTarget(self) -> PhotonTrackedTarget:
|
63
|
+
def getBestTarget(self) -> Optional[PhotonTrackedTarget]:
|
57
64
|
"""
|
58
65
|
Returns the best target in this pipeline result. If there are no targets, this method will
|
59
66
|
return null. The best target is determined by the target sort mode in the PhotonVision UI.
|
@@ -62,4 +69,4 @@ class PhotonPipelineResult:
|
|
62
69
|
return None
|
63
70
|
return self.getTargets()[0]
|
64
71
|
|
65
|
-
photonStruct: "PhotonPipelineResultSerde"
|
72
|
+
photonStruct: ClassVar["generated.PhotonPipelineResultSerde"]
|
@@ -1,8 +1,14 @@
|
|
1
1
|
from dataclasses import dataclass, field
|
2
|
+
from typing import TYPE_CHECKING, ClassVar
|
3
|
+
|
2
4
|
from wpimath.geometry import Transform3d
|
5
|
+
|
3
6
|
from ..packet import Packet
|
4
7
|
from .TargetCorner import TargetCorner
|
5
8
|
|
9
|
+
if TYPE_CHECKING:
|
10
|
+
from .. import generated
|
11
|
+
|
6
12
|
|
7
13
|
@dataclass
|
8
14
|
class PhotonTrackedTarget:
|
@@ -13,9 +19,11 @@ class PhotonTrackedTarget:
|
|
13
19
|
fiducialId: int = -1
|
14
20
|
bestCameraToTarget: Transform3d = field(default_factory=Transform3d)
|
15
21
|
altCameraToTarget: Transform3d = field(default_factory=Transform3d)
|
16
|
-
minAreaRectCorners: list[TargetCorner]
|
17
|
-
detectedCorners: list[TargetCorner]
|
22
|
+
minAreaRectCorners: list[TargetCorner] = field(default_factory=list[TargetCorner])
|
23
|
+
detectedCorners: list[TargetCorner] = field(default_factory=list[TargetCorner])
|
18
24
|
poseAmbiguity: float = 0.0
|
25
|
+
objDetectId: int = -1
|
26
|
+
objDetectConf: float = 0.0
|
19
27
|
|
20
28
|
def getYaw(self) -> float:
|
21
29
|
return self.yaw
|
@@ -35,10 +43,10 @@ class PhotonTrackedTarget:
|
|
35
43
|
def getPoseAmbiguity(self) -> float:
|
36
44
|
return self.poseAmbiguity
|
37
45
|
|
38
|
-
def getMinAreaRectCorners(self) -> list[TargetCorner]
|
46
|
+
def getMinAreaRectCorners(self) -> list[TargetCorner]:
|
39
47
|
return self.minAreaRectCorners
|
40
48
|
|
41
|
-
def getDetectedCorners(self) -> list[TargetCorner]
|
49
|
+
def getDetectedCorners(self) -> list[TargetCorner]:
|
42
50
|
return self.detectedCorners
|
43
51
|
|
44
52
|
def getBestCameraToTarget(self) -> Transform3d:
|
@@ -55,4 +63,4 @@ class PhotonTrackedTarget:
|
|
55
63
|
retList.append(TargetCorner(cx, cy))
|
56
64
|
return retList
|
57
65
|
|
58
|
-
photonStruct: "PhotonTrackedTargetSerde"
|
66
|
+
photonStruct: ClassVar["generated.PhotonTrackedTargetSerde"]
|
photonlibpy/version.py
CHANGED
@@ -1,2 +1,2 @@
|
|
1
|
-
PHOTONLIB_VERSION="v2025.0.0.
|
2
|
-
PHOTONVISION_VERSION="v2025.0.0-
|
1
|
+
PHOTONLIB_VERSION="v2025.0.0.beta.2"
|
2
|
+
PHOTONVISION_VERSION="v2025.0.0-beta-2"
|
@@ -1,13 +1,17 @@
|
|
1
1
|
Metadata-Version: 2.1
|
2
2
|
Name: photonlibpy
|
3
|
-
Version: 2025.0.
|
4
|
-
Summary: Pure-python implementation of PhotonLib for interfacing with PhotonVision on coprocessors. Implemented with PhotonVision version v2025.0.0-
|
3
|
+
Version: 2025.0.0b2
|
4
|
+
Summary: Pure-python implementation of PhotonLib for interfacing with PhotonVision on coprocessors. Implemented with PhotonVision version v2025.0.0-beta-2 .
|
5
5
|
Home-page: https://photonvision.org
|
6
6
|
Author: Photonvision Development Team
|
7
7
|
Description-Content-Type: text/markdown
|
8
|
+
Requires-Dist: numpy~=1.25
|
8
9
|
Requires-Dist: wpilib<2025,>=2024.0.0b2
|
9
10
|
Requires-Dist: robotpy-wpimath<2025,>=2024.0.0b2
|
10
11
|
Requires-Dist: robotpy-apriltag<2025,>=2024.0.0b2
|
12
|
+
Requires-Dist: robotpy-cscore<2025,>=2024.0.0.b2
|
11
13
|
Requires-Dist: pyntcore<2025,>=2024.0.0b2
|
14
|
+
Requires-Dist: opencv-python; platform_machine != "roborio"
|
15
|
+
Requires-Dist: robotpy-opencv; platform_machine == "roborio"
|
12
16
|
|
13
17
|
A Pure-python implementation of PhotonLib
|
@@ -0,0 +1,36 @@
|
|
1
|
+
photonlibpy/__init__.py,sha256=WW1OGrrcNXwwxaHSZlkxmhH2GYiQIHHxSxGVTJZhZbY,1136
|
2
|
+
photonlibpy/estimatedRobotPose.py,sha256=X7wF9xdPXGKSVy0MY0qrWZJOEbuZPd721lYp0KXKlP0,1603
|
3
|
+
photonlibpy/packet.py,sha256=5YomViVFwOljL2FGOetWM9FbPc_yCQ15ylzkYlgLIs8,9724
|
4
|
+
photonlibpy/photonCamera.py,sha256=wz55_9XoKzGX6UQ-2Oa3kjrz9KM6R7-wExiaUPkUeto,10176
|
5
|
+
photonlibpy/photonPoseEstimator.py,sha256=2iMqxPFsQHTsq95yv-WCSv1a6wXNcHPqOyMc4Bu6IG0,12584
|
6
|
+
photonlibpy/version.py,sha256=gk9q-HkZ3pUpfERPbTZbPNGvNy0gR9d01A_Db5oMkZ4,77
|
7
|
+
photonlibpy/estimation/__init__.py,sha256=pZ-d6fN1DJvT-lRl4FfIos5HAvlzmetIOrGIinrdv7k,223
|
8
|
+
photonlibpy/estimation/cameraTargetRelation.py,sha256=i7DPBXtkZve4ToXQscEIe-5F1oGQ1Qmf5QBaE__EeMQ,1158
|
9
|
+
photonlibpy/estimation/openCVHelp.py,sha256=ThJDVuJ_QFteuuSeo7wQHoE4YzPQOx60_bmFRnILS1Y,6544
|
10
|
+
photonlibpy/estimation/rotTrlTransform3d.py,sha256=nX60k9rgei7bkLRR3Ykl2lhnjpsiSNuImk6fERFcy2w,915
|
11
|
+
photonlibpy/estimation/targetModel.py,sha256=e5IaDKFdNtek6pJLrzw2poit5wxvraIRtHPDmN-rqUk,4416
|
12
|
+
photonlibpy/estimation/visionEstimation.py,sha256=jCOBHHOjhzjNOD-_kn-jpTOXqlGxek24oKL51GiRSKU,2999
|
13
|
+
photonlibpy/generated/MultiTargetPNPResultSerde.py,sha256=WoCdln8kkciBltG-YdFn5OjdLGMD3VwwHymfe95QF4s,2342
|
14
|
+
photonlibpy/generated/PhotonPipelineMetadataSerde.py,sha256=0beAVUFeQ1Shq5ku4q5IgE-sYkMzk3XoemRnC5Vx8Hg,2767
|
15
|
+
photonlibpy/generated/PhotonPipelineResultSerde.py,sha256=q2w8ei-8X1ZJgHnYsTfX7NHTybUboP-DqQkdGY5bj1M,2847
|
16
|
+
photonlibpy/generated/PhotonTrackedTargetSerde.py,sha256=TT18q7jb2WzcPDOf26NOo1l23W9gY80CyrNYUBXbHYs,4271
|
17
|
+
photonlibpy/generated/PnpResultSerde.py,sha256=FVvv34GzQ856uGobpRSUO8TbV-h7IVipkTqgqfRa35Y,2586
|
18
|
+
photonlibpy/generated/TargetCornerSerde.py,sha256=rUJUBfs02gTWgkHvSjuaGLQdSzZcfpRRcSLDlFo8-_E,2080
|
19
|
+
photonlibpy/generated/__init__.py,sha256=mElM8M88---wxTWO-SRqIJ4EfxN0fdIUwZBZ-UIGuRw,428
|
20
|
+
photonlibpy/networktables/NTTopicSet.py,sha256=9jagxRAxO6nN7LvHZti86qA9V_d9_FStoDz5C3siM7Y,2545
|
21
|
+
photonlibpy/networktables/__init__.py,sha256=o_LxTdyIylAszMy_zhUtTkXHyu6jqxccccj78d44OrI,35
|
22
|
+
photonlibpy/simulation/__init__.py,sha256=HKJV02of5d8bOnuI7syLzSYtOYge7XUrHSaLvawh99M,227
|
23
|
+
photonlibpy/simulation/photonCameraSim.py,sha256=xul2eXUe1XgJ-RWALG6cgU4zDPcDOvHHvjFjAASS188,14706
|
24
|
+
photonlibpy/simulation/simCameraProperties.py,sha256=LAmxwm9FSyx-CTsVO-TRhfn4Pz5oanJV0Jh7KUnCNgM,20557
|
25
|
+
photonlibpy/simulation/videoSimUtil.py,sha256=xMuTvJ2Jx9IoQqmAJi_zUm06MdEwhVpIz9OyzYQp0k4,29
|
26
|
+
photonlibpy/simulation/visionSystemSim.py,sha256=q4ifF4q_XkCJ9jIkHBX6lYY6INc-uvFBi4c2OLQR3WA,8615
|
27
|
+
photonlibpy/simulation/visionTargetSim.py,sha256=AN7jXW3guQfNUu2EiQl23Jj8Mkgn4gYmRphGXL0-Dqk,1734
|
28
|
+
photonlibpy/targeting/TargetCorner.py,sha256=5a7RdK_WLCgui7BVE3KnHmb3jHbXeM5_SfFSDbnmd0M,251
|
29
|
+
photonlibpy/targeting/__init__.py,sha256=YzINSpq6A0cjr-yAQcFqHoiYdLGKPFXThlVYlMjY11w,295
|
30
|
+
photonlibpy/targeting/multiTargetPNPResult.py,sha256=zcUF1rIAgovURXu9saiLHIjuspSpRn3r7-J6tB_YlU4,1125
|
31
|
+
photonlibpy/targeting/photonPipelineResult.py,sha256=Sy_KBvI0ps1pQOJ80XYHTrz50aqUDBcuvIC_b1ku3G4,2617
|
32
|
+
photonlibpy/targeting/photonTrackedTarget.py,sha256=m6y-dBqP8iVt5J0WcGDxYpmgctVy6SNL358ZY1YgjCc,1917
|
33
|
+
photonlibpy-2025.0.0b2.dist-info/METADATA,sha256=EdH_l3RSbxbU8Z2s7SIBpIwca7DCOPRaOwVuniX1fro,752
|
34
|
+
photonlibpy-2025.0.0b2.dist-info/WHEEL,sha256=bFJAMchF8aTQGUgMZzHJyDDMPTO3ToJ7x23SLJa1SVo,92
|
35
|
+
photonlibpy-2025.0.0b2.dist-info/top_level.txt,sha256=T8Xc6U6he2VjKUAca6zawSkHdUZuLanxYIc4nxw2ctc,12
|
36
|
+
photonlibpy-2025.0.0b2.dist-info/RECORD,,
|
@@ -1,22 +0,0 @@
|
|
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,,
|
File without changes
|