photonlibpy 2025.0.0b2__py3-none-any.whl → 2025.0.0b4__py3-none-any.whl

Sign up to get free protection for your applications and to get access to all the features.
@@ -15,7 +15,22 @@ from .visionTargetSim import VisionTargetSim
15
15
 
16
16
 
17
17
  class VisionSystemSim:
18
+ """A simulated vision system involving a camera(s) and coprocessor(s) mounted on a mobile robot
19
+ running PhotonVision, detecting targets placed on the field. :class:`.VisionTargetSim`s added to
20
+ this class will be detected by the :class:`.PhotonCameraSim`s added to this class. This class
21
+ should be updated periodically with the robot's current pose in order to publish the simulated
22
+ camera target info.
23
+ """
24
+
18
25
  def __init__(self, visionSystemName: str):
26
+ """A simulated vision system involving a camera(s) and coprocessor(s) mounted on a mobile robot
27
+ running PhotonVision, detecting targets placed on the field. :class:`.VisionTargetSim`s added to
28
+ this class will be detected by the :class:`.PhotonCameraSim`s added to this class. This class
29
+ should be updated periodically with the robot's current pose in order to publish the simulated
30
+ camera target info.
31
+
32
+ :param visionSystemName: The specific identifier for this vision system in NetworkTables.
33
+ """
19
34
  self.dbgField: Field2d = Field2d()
20
35
  self.bufferLength: seconds = 1.5
21
36
 
@@ -32,12 +47,21 @@ class VisionSystemSim:
32
47
  wpilib.SmartDashboard.putData(self.tableName + "/Sim Field", self.dbgField)
33
48
 
34
49
  def getCameraSim(self, name: str) -> PhotonCameraSim | None:
50
+ """Get one of the simulated cameras."""
35
51
  return self.camSimMap.get(name, None)
36
52
 
37
53
  def getCameraSims(self) -> list[PhotonCameraSim]:
54
+ """Get all the simulated cameras."""
38
55
  return [*self.camSimMap.values()]
39
56
 
40
57
  def addCamera(self, cameraSim: PhotonCameraSim, robotToCamera: Transform3d) -> None:
58
+ """Adds a simulated camera to this vision system with a specified robot-to-camera transformation.
59
+ The vision targets registered with this vision system simulation will be observed by the
60
+ simulated :class:`.PhotonCamera`.
61
+
62
+ :param cameraSim: The camera simulation
63
+ :param robotToCamera: The transform from the robot pose to the camera pose
64
+ """
41
65
  name = cameraSim.getCamera().getName()
42
66
  if name not in self.camSimMap:
43
67
  self.camSimMap[name] = cameraSim
@@ -49,10 +73,15 @@ class VisionSystemSim:
49
73
  )
50
74
 
51
75
  def clearCameras(self) -> None:
76
+ """Remove all simulated cameras from this vision system."""
52
77
  self.camSimMap.clear()
53
78
  self.camTrfMap.clear()
54
79
 
55
80
  def removeCamera(self, cameraSim: PhotonCameraSim) -> bool:
81
+ """Remove a simulated camera from this vision system.
82
+
83
+ :returns: If the camera was present and removed
84
+ """
56
85
  name = cameraSim.getCamera().getName()
57
86
  if name in self.camSimMap:
58
87
  del self.camSimMap[name]
@@ -65,6 +94,14 @@ class VisionSystemSim:
65
94
  cameraSim: PhotonCameraSim,
66
95
  time: seconds = wpilib.Timer.getFPGATimestamp(),
67
96
  ) -> Transform3d | None:
97
+ """Get a simulated camera's position relative to the robot. If the requested camera is invalid, an
98
+ empty optional is returned.
99
+
100
+ :param cameraSim: The specific camera to get the robot-to-camera transform of
101
+ :param timeSeconds: Timestamp in seconds of when the transform should be observed
102
+
103
+ :returns: The transform of this camera, or an empty optional if it is invalid
104
+ """
68
105
  if cameraSim in self.camTrfMap:
69
106
  trfBuffer = self.camTrfMap[cameraSim]
70
107
  sample = trfBuffer.sample(time)
@@ -80,15 +117,34 @@ class VisionSystemSim:
80
117
  cameraSim: PhotonCameraSim,
81
118
  time: seconds = wpilib.Timer.getFPGATimestamp(),
82
119
  ) -> Pose3d | None:
120
+ """Get a simulated camera's position on the field. If the requested camera is invalid, an empty
121
+ optional is returned.
122
+
123
+ :param cameraSim: The specific camera to get the field pose of
124
+
125
+ :returns: The pose of this camera, or an empty optional if it is invalid
126
+ """
83
127
  robotToCamera = self.getRobotToCamera(cameraSim, time)
84
128
  if robotToCamera is None:
85
129
  return None
86
130
  else:
87
- return self.getRobotPose(time) + robotToCamera
131
+ pose = self.getRobotPose(time)
132
+ if pose:
133
+ return pose + robotToCamera
134
+ else:
135
+ return None
88
136
 
89
137
  def adjustCamera(
90
138
  self, cameraSim: PhotonCameraSim, robotToCamera: Transform3d
91
139
  ) -> bool:
140
+ """Adjust a camera's position relative to the robot. Use this if your camera is on a gimbal or
141
+ turret or some other mobile platform.
142
+
143
+ :param cameraSim: The simulated camera to change the relative position of
144
+ :param robotToCamera: New transform from the robot to the camera
145
+
146
+ :returns: If the cameraSim was valid and transform was adjusted
147
+ """
92
148
  if cameraSim in self.camTrfMap:
93
149
  self.camTrfMap[cameraSim].addSample(
94
150
  wpilib.Timer.getFPGATimestamp(), Pose3d() + robotToCamera
@@ -98,6 +154,7 @@ class VisionSystemSim:
98
154
  return False
99
155
 
100
156
  def resetCameraTransforms(self, cameraSim: PhotonCameraSim | None = None) -> None:
157
+ """Reset the transform history for this camera to just the current transform."""
101
158
  now = wpilib.Timer.getFPGATimestamp()
102
159
 
103
160
  def resetSingleCamera(self, cameraSim: PhotonCameraSim) -> bool:
@@ -129,12 +186,30 @@ class VisionSystemSim:
129
186
  def addVisionTargets(
130
187
  self, targets: list[VisionTargetSim], targetType: str = "targets"
131
188
  ) -> None:
189
+ """Adds targets on the field which your vision system is designed to detect. The {@link
190
+ PhotonCamera}s simulated from this system will report the location of the camera relative to
191
+ the subset of these targets which are visible from the given camera position.
192
+
193
+ :param targets: Targets to add to the simulated field
194
+ :param type: Type of target (e.g. "cargo").
195
+ """
196
+
132
197
  if targetType not in self.targetSets:
133
198
  self.targetSets[targetType] = targets
134
199
  else:
135
200
  self.targetSets[targetType] += targets
136
201
 
137
202
  def addAprilTags(self, layout: AprilTagFieldLayout) -> None:
203
+ """Adds targets on the field which your vision system is designed to detect. The {@link
204
+ PhotonCamera}s simulated from this system will report the location of the camera relative to
205
+ the subset of these targets which are visible from the given camera position.
206
+
207
+ The AprilTags from this layout will be added as vision targets under the type "apriltag".
208
+ The poses added preserve the tag layout's current alliance origin. If the tag layout's alliance
209
+ origin is changed, these added tags will have to be cleared and re-added.
210
+
211
+ :param tagLayout: The field tag layout to get Apriltag poses and IDs from
212
+ """
138
213
  targets: list[VisionTargetSim] = []
139
214
  for tag in layout.getTags():
140
215
  tag_pose = layout.getTagPose(tag.ID)
@@ -167,10 +242,16 @@ class VisionSystemSim:
167
242
 
168
243
  def getRobotPose(
169
244
  self, timestamp: seconds = wpilib.Timer.getFPGATimestamp()
170
- ) -> Pose3d:
245
+ ) -> Pose3d | None:
246
+ """Get the robot pose in meters saved by the vision system at this timestamp.
247
+
248
+ :param timestamp: Timestamp of the desired robot pose
249
+ """
250
+
171
251
  return self.robotPoseBuffer.sample(timestamp)
172
252
 
173
253
  def resetRobotPose(self, robotPose: Pose2d | Pose3d) -> None:
254
+ """Clears all previous robot poses and sets robotPose at current time."""
174
255
  if type(robotPose) is Pose2d:
175
256
  robotPose = Pose3d(robotPose)
176
257
  assert type(robotPose) is Pose3d
@@ -182,16 +263,23 @@ class VisionSystemSim:
182
263
  return self.dbgField
183
264
 
184
265
  def update(self, robotPose: Pose2d | Pose3d) -> None:
266
+ """Periodic update. Ensure this is called repeatedly-- camera performance is used to automatically
267
+ determine if a new frame should be submitted.
268
+
269
+ :param robotPoseMeters: The simulated robot pose in meters
270
+ """
185
271
  if type(robotPose) is Pose2d:
186
272
  robotPose = Pose3d(robotPose)
187
273
  assert type(robotPose) is Pose3d
188
274
 
275
+ # update vision targets on field
189
276
  for targetType, targets in self.targetSets.items():
190
277
  posesToAdd: list[Pose2d] = []
191
278
  for target in targets:
192
279
  posesToAdd.append(target.getPose().toPose2d())
193
280
  self.dbgField.getObject(targetType).setPoses(posesToAdd)
194
281
 
282
+ # save "real" robot poses over time
195
283
  now = wpilib.Timer.getFPGATimestamp()
196
284
  self.robotPoseBuffer.addSample(now, robotPose)
197
285
  self.dbgField.setRobotPose(robotPose.toPose2d())
@@ -204,27 +292,36 @@ class VisionSystemSim:
204
292
  visTgtPoses2d: list[Pose2d] = []
205
293
  cameraPoses2d: list[Pose2d] = []
206
294
  processed = False
295
+ # process each camera
207
296
  for camSim in self.camSimMap.values():
297
+ # check if this camera is ready to process and get latency
208
298
  optTimestamp = camSim.consumeNextEntryTime()
209
299
  if optTimestamp is None:
210
300
  continue
211
301
  else:
212
302
  processed = True
213
303
 
304
+ # when this result "was" read by NT
214
305
  timestampNt = optTimestamp
215
306
  latency = camSim.prop.estLatency()
307
+ # the image capture timestamp in seconds of this result
216
308
  timestampCapture = timestampNt * 1.0e-6 - latency
217
309
 
310
+ # use camera pose from the image capture timestamp
218
311
  lateRobotPose = self.getRobotPose(timestampCapture)
219
- lateCameraPose = lateRobotPose + self.getRobotToCamera(
220
- camSim, timestampCapture
221
- )
312
+ robotToCamera = self.getRobotToCamera(camSim, timestampCapture)
313
+ if lateRobotPose is None or robotToCamera is None:
314
+ return None
315
+ lateCameraPose = lateRobotPose + robotToCamera
222
316
  cameraPoses2d.append(lateCameraPose.toPose2d())
223
317
 
318
+ # process a PhotonPipelineResult with visible targets
224
319
  camResult = camSim.process(latency, lateCameraPose, allTargets)
320
+ # publish this info to NT at estimated timestamp of receive
225
321
  camSim.submitProcessedFrame(camResult, timestampNt)
226
- for target in camResult.getTargets():
227
- trf = target.getBestCameraToTarget()
322
+ # display debug results
323
+ for tgt in camResult.getTargets():
324
+ trf = tgt.getBestCameraToTarget()
228
325
  if trf == Transform3d():
229
326
  continue
230
327
 
@@ -6,7 +6,16 @@ from ..estimation.targetModel import TargetModel
6
6
 
7
7
 
8
8
  class VisionTargetSim:
9
+ """Describes a vision target located somewhere on the field that your vision system can detect."""
10
+
9
11
  def __init__(self, pose: Pose3d, model: TargetModel, id: int = -1):
12
+ """Describes a fiducial tag located somewhere on the field that your vision system can detect.
13
+
14
+ :param pose: Pose3d of the tag in field-relative coordinates
15
+ :param model: TargetModel which describes the shape of the target(tag)
16
+ :param id: The ID of this fiducial tag
17
+ """
18
+
10
19
  self.pose: Pose3d = pose
11
20
  self.model: TargetModel = model
12
21
  self.fiducialId: int = id
@@ -47,4 +56,5 @@ class VisionTargetSim:
47
56
  return self.model
48
57
 
49
58
  def getFieldVertices(self) -> list[Translation3d]:
59
+ """This target's vertices offset from its field pose."""
50
60
  return self.model.getFieldVertices(self.pose)
@@ -2,7 +2,7 @@ from dataclasses import dataclass
2
2
  from typing import TYPE_CHECKING, ClassVar
3
3
 
4
4
  if TYPE_CHECKING:
5
- from .. import generated
5
+ from ..generated.TargetCornerSerde import TargetCornerSerde
6
6
 
7
7
 
8
8
  @dataclass
@@ -10,4 +10,4 @@ class TargetCorner:
10
10
  x: float = 0
11
11
  y: float = 9
12
12
 
13
- photonStruct: ClassVar["generated.TargetCornerSerde"]
13
+ photonStruct: ClassVar["TargetCornerSerde"]
@@ -3,10 +3,9 @@ from typing import TYPE_CHECKING, ClassVar
3
3
 
4
4
  from wpimath.geometry import Transform3d
5
5
 
6
- from ..packet import Packet
7
-
8
6
  if TYPE_CHECKING:
9
- from .. import generated
7
+ from ..generated.MultiTargetPNPResultSerde import MultiTargetPNPResultSerde
8
+ from ..generated.PnpResultSerde import PnpResultSerde
10
9
 
11
10
 
12
11
  @dataclass
@@ -17,7 +16,7 @@ class PnpResult:
17
16
  bestReprojErr: float = 0.0
18
17
  altReprojErr: float = 0.0
19
18
 
20
- photonStruct: ClassVar["generated.PnpResultSerde"]
19
+ photonStruct: ClassVar["PnpResultSerde"]
21
20
 
22
21
 
23
22
  @dataclass
@@ -27,14 +26,4 @@ class MultiTargetPNPResult:
27
26
  estimatedPose: PnpResult = field(default_factory=PnpResult)
28
27
  fiducialIDsUsed: list[int] = field(default_factory=list)
29
28
 
30
- def createFromPacket(self, packet: Packet) -> Packet:
31
- self.estimatedPose = PnpResult()
32
- self.estimatedPose.createFromPacket(packet)
33
- self.fiducialIDsUsed = []
34
- for _ in range(MultiTargetPNPResult._MAX_IDS):
35
- fidId = packet.decode16()
36
- if fidId >= 0:
37
- self.fiducialIDsUsed.append(fidId)
38
- return packet
39
-
40
- photonStruct: ClassVar["generated.MultiTargetPNPResultSerde"]
29
+ photonStruct: ClassVar["MultiTargetPNPResultSerde"]
@@ -5,7 +5,8 @@ from .multiTargetPNPResult import MultiTargetPNPResult
5
5
  from .photonTrackedTarget import PhotonTrackedTarget
6
6
 
7
7
  if TYPE_CHECKING:
8
- from .. import generated
8
+ from ..generated.PhotonPipelineMetadataSerde import PhotonPipelineMetadataSerde
9
+ from ..generated.PhotonPipelineResultSerde import PhotonPipelineResultSerde
9
10
 
10
11
 
11
12
  @dataclass
@@ -20,7 +21,7 @@ class PhotonPipelineMetadata:
20
21
 
21
22
  timeSinceLastPong: int = -1
22
23
 
23
- photonStruct: ClassVar["generated.PhotonPipelineMetadataSerde"]
24
+ photonStruct: ClassVar["PhotonPipelineMetadataSerde"]
24
25
 
25
26
 
26
27
  @dataclass
@@ -69,4 +70,4 @@ class PhotonPipelineResult:
69
70
  return None
70
71
  return self.getTargets()[0]
71
72
 
72
- photonStruct: ClassVar["generated.PhotonPipelineResultSerde"]
73
+ photonStruct: ClassVar["PhotonPipelineResultSerde"]
@@ -7,7 +7,7 @@ from ..packet import Packet
7
7
  from .TargetCorner import TargetCorner
8
8
 
9
9
  if TYPE_CHECKING:
10
- from .. import generated
10
+ from ..generated.PhotonTrackedTargetSerde import PhotonTrackedTargetSerde
11
11
 
12
12
 
13
13
  @dataclass
@@ -63,4 +63,4 @@ class PhotonTrackedTarget:
63
63
  retList.append(TargetCorner(cx, cy))
64
64
  return retList
65
65
 
66
- photonStruct: ClassVar["generated.PhotonTrackedTargetSerde"]
66
+ photonStruct: ClassVar["PhotonTrackedTargetSerde"]
photonlibpy/version.py CHANGED
@@ -1,2 +1,2 @@
1
- PHOTONLIB_VERSION="v2025.0.0.beta.2"
2
- PHOTONVISION_VERSION="v2025.0.0-beta-2"
1
+ PHOTONLIB_VERSION="v2025.0.0.beta.4"
2
+ PHOTONVISION_VERSION="v2025.0.0-beta-4"
@@ -1,17 +1,16 @@
1
1
  Metadata-Version: 2.1
2
2
  Name: photonlibpy
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 .
3
+ Version: 2025.0.0b4
4
+ Summary: Pure-python implementation of PhotonLib for interfacing with PhotonVision on coprocessors. Implemented with PhotonVision version v2025.0.0-beta-4 .
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
9
- Requires-Dist: wpilib<2025,>=2024.0.0b2
10
- Requires-Dist: robotpy-wpimath<2025,>=2024.0.0b2
11
- Requires-Dist: robotpy-apriltag<2025,>=2024.0.0b2
12
- Requires-Dist: robotpy-cscore<2025,>=2024.0.0.b2
13
- Requires-Dist: pyntcore<2025,>=2024.0.0b2
8
+ Requires-Dist: numpy~=2.1
9
+ Requires-Dist: wpilib<2026,>=2025.0.0b1
10
+ Requires-Dist: robotpy-wpimath<2026,>=2025.0.0b1
11
+ Requires-Dist: robotpy-apriltag<2026,>=2025.0.0b1
12
+ Requires-Dist: robotpy-cscore<2026,>=2025.0.0b1
13
+ Requires-Dist: pyntcore<2026,>=2025.0.0b1
14
14
  Requires-Dist: opencv-python; platform_machine != "roborio"
15
- Requires-Dist: robotpy-opencv; platform_machine == "roborio"
16
15
 
17
16
  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=80-UKakvcgJ79vw80e2yUqZZfoQtpC1_lopnXpfgvOY,12823
5
+ photonlibpy/photonPoseEstimator.py,sha256=2iMqxPFsQHTsq95yv-WCSv1a6wXNcHPqOyMc4Bu6IG0,12584
6
+ photonlibpy/version.py,sha256=Ew1xD5CpZetX_p3ReR01MPCVsroMfk2ZpgH42q0Fubg,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=h36tOunGaDfs1yp1kAyK-BX0DqdNXZSN8T8ms-ReQas,12277
10
+ photonlibpy/estimation/rotTrlTransform3d.py,sha256=oRYk4V1XF7guNxefJsCPcBWPIkKZl0HYD_Gs86wwToE,2671
11
+ photonlibpy/estimation/targetModel.py,sha256=fIhkf0-_Sfv-KhYEBnhFWMF4Xu84FfF6B-KUEsuuGjQ,6459
12
+ photonlibpy/estimation/visionEstimation.py,sha256=Q4KWdLCV1H0wJUJCzG7OYNhVmk2jR1iPUmX_PFylLdA,4174
13
+ photonlibpy/generated/MultiTargetPNPResultSerde.py,sha256=CzsCosHUnzxAoSC_sSAqpsXsDp54KW-BClnIXdzfMPc,2506
14
+ photonlibpy/generated/PhotonPipelineMetadataSerde.py,sha256=9pq5XUEDEoRowCd7sRnuGV7xtugu5HZCRrnwqZG2xXc,2887
15
+ photonlibpy/generated/PhotonPipelineResultSerde.py,sha256=jTf1obU2jPNDsxvt-tl9Ty_qzJws9Wqron3C1QiHkP8,3137
16
+ photonlibpy/generated/PhotonTrackedTargetSerde.py,sha256=-6vKir_ABDVBGbg8ktM48IKm_nBMFBbiyuZLiO_fP9U,4437
17
+ photonlibpy/generated/PnpResultSerde.py,sha256=YoTKdQ51oSdxC-7Poy6hunL0-zkMKvP5uedqaHWPudY,2693
18
+ photonlibpy/generated/TargetCornerSerde.py,sha256=kziD_rQIwyhzPfgOaDgn-3d87tvtXiAYbBjzu76biYU,2190
19
+ photonlibpy/generated/__init__.py,sha256=mElM8M88---wxTWO-SRqIJ4EfxN0fdIUwZBZ-UIGuRw,428
20
+ photonlibpy/networktables/NTTopicSet.py,sha256=TXJyVg6S8gONeuRqX_NI0FdxYw51bNLlFIAQ4Y2wyVg,3104
21
+ photonlibpy/networktables/__init__.py,sha256=o_LxTdyIylAszMy_zhUtTkXHyu6jqxccccj78d44OrI,35
22
+ photonlibpy/simulation/__init__.py,sha256=HKJV02of5d8bOnuI7syLzSYtOYge7XUrHSaLvawh99M,227
23
+ photonlibpy/simulation/photonCameraSim.py,sha256=5GTPdU7SRAahhtXYHcbm0GJEzARWA7lyBG3v279pqGk,19891
24
+ photonlibpy/simulation/simCameraProperties.py,sha256=bJ6Xvos2glO0-R_a0Wv4eKESnQD13GSYqhwPQdVr1eQ,27082
25
+ photonlibpy/simulation/videoSimUtil.py,sha256=xMuTvJ2Jx9IoQqmAJi_zUm06MdEwhVpIz9OyzYQp0k4,29
26
+ photonlibpy/simulation/visionSystemSim.py,sha256=ln1TYVMXUreg6nxrVZJ7lw8puvgLbBBde_ciM2CH5G4,13788
27
+ photonlibpy/simulation/visionTargetSim.py,sha256=FH85fKE4NntowUvssfgZ1KlE-I_3Z-QuAgb2bFqvfdY,2219
28
+ photonlibpy/targeting/TargetCorner.py,sha256=ouKj3E5uD76OZSNHHuSDzKOY65a8HqtcOsuejH-MVsU,276
29
+ photonlibpy/targeting/__init__.py,sha256=YzINSpq6A0cjr-yAQcFqHoiYdLGKPFXThlVYlMjY11w,295
30
+ photonlibpy/targeting/multiTargetPNPResult.py,sha256=Y9rweHtMzoCZ6mv6F8CutQi2Thq5pHN0ydBWvTCsOwY,806
31
+ photonlibpy/targeting/photonPipelineResult.py,sha256=MbaSyHZTJpoKTtLOZztpSGSt9xWWFqhzgwj8medObVA,2732
32
+ photonlibpy/targeting/photonTrackedTarget.py,sha256=zCoFp32hX-3GmBYEmsYBQieBoMzXtP2F_55_q0zPOXA,1956
33
+ photonlibpy-2025.0.0b4.dist-info/METADATA,sha256=zybpLt0J7EMylub2yKyAugXJ-lt7-uwrAhFV7KGv51U,689
34
+ photonlibpy-2025.0.0b4.dist-info/WHEEL,sha256=bFJAMchF8aTQGUgMZzHJyDDMPTO3ToJ7x23SLJa1SVo,92
35
+ photonlibpy-2025.0.0b4.dist-info/top_level.txt,sha256=T8Xc6U6he2VjKUAca6zawSkHdUZuLanxYIc4nxw2ctc,12
36
+ photonlibpy-2025.0.0b4.dist-info/RECORD,,
@@ -1,36 +0,0 @@
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,,