Skip to content

Commit 29e24bb

Browse files
kcooneysamfreund
andauthored
[photon-lib] Python support for PNP_DISTANCE_TRIG_SOLVE (#2015)
This adds support for PNP_DISTANCE_TRIG_SOLVE in the the python PhotonPoseEstimator, mirroring the implementation in the Java PhotonPoseEstimator. Changes: - Add PoseStrategy.PNP_DISTANCE_TRIG_SOLVE - Add addHeadingData() and resetHeadingData() to PhotonPoseEstimator - Fix PhotonCameraSim.process() to set ntReceiveTimestampMicros in the result - Minor readability improvements to PhotonPipelineResult - Minor test improvements to PhotonPoseEstimatorTest - Add .vscode/settings.json (to make running python tests in VSCode easier) Merge checklist: - [x] Pull Request title is [short, imperative summary](https://cbea.ms/git-commit/) of proposed changes - [x] The description documents the _what_ and _why_ - [ ] If this PR changes behavior or adds a feature, user documentation is updated - [ ] If this PR touches photon-serde, all messages have been regenerated and hashes have not changed unexpectedly - [ ] If this PR touches configuration, this is backwards compatible with settings back to v2024.3.1 - [ ] If this PR touches pipeline settings or anything related to data exchange, the frontend typing is updated - [ ] If this PR addresses a bug, a regression test for it is added --------- Co-authored-by: Sam948-byte <samf.236@proton.me>
1 parent cefaa31 commit 29e24bb

File tree

7 files changed

+259
-74
lines changed

7 files changed

+259
-74
lines changed

.gitignore

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,8 @@ __pycache__/
55

66
/.vs
77
backend/settings/
8-
.vscode/
8+
.vscode/*
9+
!.vscode/settings.json
910
# Docs
1011
_build
1112
# Compiled class file

.vscode/settings.json

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
{
2+
"python.testing.unittestEnabled": false,
3+
"python.testing.pytestEnabled": true,
4+
"python.testing.cwd": "photon-lib/py"
5+
}

photon-lib/py/photonlibpy/photonPoseEstimator.py

Lines changed: 97 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -20,8 +20,18 @@
2020

2121
import hal
2222
import wpilib
23+
import wpimath.units
2324
from robotpy_apriltag import AprilTagFieldLayout
24-
from wpimath.geometry import Pose2d, Pose3d, Transform3d
25+
from wpimath.geometry import (
26+
Pose2d,
27+
Pose3d,
28+
Rotation2d,
29+
Rotation3d,
30+
Transform3d,
31+
Translation2d,
32+
Translation3d,
33+
)
34+
from wpimath.interpolation import TimeInterpolatableRotation2dBuffer
2535

2636
from .estimatedRobotPose import EstimatedRobotPose
2737
from .photonCamera import PhotonCamera
@@ -60,6 +70,17 @@ class PoseStrategy(enum.Enum):
6070
This runs on the RoboRIO, and can take a lot of time.
6171
"""
6272

73+
PNP_DISTANCE_TRIG_SOLVE = enum.auto()
74+
"""
75+
Use distance data from best visible tag to compute a Pose. This runs on
76+
the RoboRIO in order to access the robot's yaw heading, and MUST have
77+
addHeadingData called every frame so heading data is up-to-date.
78+
79+
Produces a Pose2d in estimatedRobotPose (0 for z, roll, pitch).
80+
81+
See https://www.chiefdelphi.com/t/frc-6328-mechanical-advantage-2025-build-thread/477314/98
82+
"""
83+
6384

6485
class PhotonPoseEstimator:
6586
instance_count = 1
@@ -98,6 +119,7 @@ def __init__(
98119
self._poseCacheTimestampSeconds = -1.0
99120
self._lastPose: Optional[Pose3d] = None
100121
self._referencePose: Optional[Pose3d] = None
122+
self._headingBuffer = TimeInterpolatableRotation2dBuffer(1)
101123

102124
# Usage reporting
103125
hal.report(
@@ -210,6 +232,32 @@ def _checkUpdate(self, oldObj, newObj) -> None:
210232
if oldObj != newObj and oldObj is not None and oldObj is not newObj:
211233
self._invalidatePoseCache()
212234

235+
def addHeadingData(
236+
self, timestampSeconds: wpimath.units.seconds, heading: Rotation2d | Rotation3d
237+
) -> None:
238+
"""
239+
Add robot heading data to buffer. Must be called periodically for the **PNP_DISTANCE_TRIG_SOLVE** strategy.
240+
241+
:param timestampSeconds :timestamp of the robot heading data
242+
:param heading: field-relative robot heading at given timestamp
243+
"""
244+
if isinstance(heading, Rotation3d):
245+
heading = heading.toRotation2d()
246+
self._headingBuffer.addSample(timestampSeconds, heading)
247+
248+
def resetHeadingData(
249+
self, timestampSeconds: wpimath.units.seconds, heading: Rotation2d | Rotation3d
250+
) -> None:
251+
"""
252+
Clears all heading data in the buffer, and adds a new seed. Useful for preventing estimates
253+
from utilizing heading data provided prior to a pose or rotation reset.
254+
255+
:param timestampSeconds: timestamp of the robot heading data
256+
:param heading: field-relative robot heading at given timestamp
257+
"""
258+
self._headingBuffer.clear()
259+
self.addHeadingData(timestampSeconds, heading)
260+
213261
def update(
214262
self, cameraResult: Optional[PhotonPipelineResult] = None
215263
) -> Optional[EstimatedRobotPose]:
@@ -263,6 +311,8 @@ def _update(
263311
estimatedPose = self._lowestAmbiguityStrategy(cameraResult)
264312
elif strat is PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR:
265313
estimatedPose = self._multiTagOnCoprocStrategy(cameraResult)
314+
elif strat is PoseStrategy.PNP_DISTANCE_TRIG_SOLVE:
315+
estimatedPose = self._pnpDistanceTrigSolveStrategy(cameraResult)
266316
else:
267317
wpilib.reportError(
268318
"[PhotonPoseEstimator] Unknown Position Estimation Strategy!", False
@@ -274,6 +324,52 @@ def _update(
274324

275325
return estimatedPose
276326

327+
def _pnpDistanceTrigSolveStrategy(
328+
self, result: PhotonPipelineResult
329+
) -> Optional[EstimatedRobotPose]:
330+
if (bestTarget := result.getBestTarget()) is None:
331+
return None
332+
333+
if (
334+
headingSample := self._headingBuffer.sample(result.getTimestampSeconds())
335+
) is None:
336+
return None
337+
338+
if (tagPose := self._fieldTags.getTagPose(bestTarget.fiducialId)) is None:
339+
return None
340+
341+
camToTagTranslation = (
342+
Translation3d(
343+
bestTarget.getBestCameraToTarget().translation().norm(),
344+
Rotation3d(
345+
0,
346+
-wpimath.units.degreesToRadians(bestTarget.getPitch()),
347+
-wpimath.units.degreesToRadians(bestTarget.getYaw()),
348+
),
349+
)
350+
.rotateBy(self.robotToCamera.rotation())
351+
.toTranslation2d()
352+
.rotateBy(headingSample)
353+
)
354+
355+
fieldToCameraTranslation = (
356+
tagPose.toPose2d().translation() - camToTagTranslation
357+
)
358+
camToRobotTranslation: Translation2d = -(
359+
self.robotToCamera.translation().toTranslation2d()
360+
)
361+
camToRobotTranslation = camToRobotTranslation.rotateBy(headingSample)
362+
robotPose = Pose2d(
363+
fieldToCameraTranslation + camToRobotTranslation, headingSample
364+
)
365+
366+
return EstimatedRobotPose(
367+
Pose3d(robotPose),
368+
result.getTimestampSeconds(),
369+
result.getTargets(),
370+
PoseStrategy.PNP_DISTANCE_TRIG_SOLVE,
371+
)
372+
277373
def _multiTagOnCoprocStrategy(
278374
self, result: PhotonPipelineResult
279375
) -> Optional[EstimatedRobotPose]:

photon-lib/py/photonlibpy/simulation/photonCameraSim.py

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -420,14 +420,15 @@ def distance(target: VisionTargetSim):
420420

421421
# put this simulated data to NT
422422
self.heartbeatCounter += 1
423-
now_micros = wpilib.Timer.getFPGATimestamp() * 1e6
423+
publishTimestampMicros = wpilib.Timer.getFPGATimestamp() * 1e6
424424
return PhotonPipelineResult(
425+
ntReceiveTimestampMicros=int(publishTimestampMicros + 10),
425426
metadata=PhotonPipelineMetadata(
426-
int(now_micros - latency * 1e6),
427-
int(now_micros),
428-
self.heartbeatCounter,
427+
captureTimestampMicros=int(publishTimestampMicros - latency * 1e6),
428+
publishTimestampMicros=int(publishTimestampMicros),
429+
sequenceID=self.heartbeatCounter,
429430
# Pretend like we heard a pong recently
430-
int(np.random.uniform(950, 1050)),
431+
timeSinceLastPong=int(np.random.uniform(950, 1050)),
431432
),
432433
targets=detectableTgts,
433434
multitagResult=multiTagResults,

photon-lib/py/photonlibpy/targeting/photonPipelineResult.py

Lines changed: 4 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -47,13 +47,10 @@ def getTimestampSeconds(self) -> float:
4747
timestamp, coproc timebase))
4848
"""
4949
# TODO - we don't trust NT4 to correctly latency-compensate ntReceiveTimestampMicros
50-
return (
51-
self.ntReceiveTimestampMicros
52-
- (
53-
self.metadata.publishTimestampMicros
54-
- self.metadata.captureTimestampMicros
55-
)
56-
) / 1e6
50+
latency = (
51+
self.metadata.publishTimestampMicros - self.metadata.captureTimestampMicros
52+
)
53+
return (self.ntReceiveTimestampMicros - latency) / 1e6
5754

5855
def getTargets(self) -> list[PhotonTrackedTarget]:
5956
return self.targets

photon-lib/py/test/photonPoseEstimator_test.py

Lines changed: 91 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,10 @@
1515
## along with this program. If not, see <https://www.gnu.org/licenses/>.
1616
###############################################################################
1717

18-
from photonlibpy import PhotonPoseEstimator, PoseStrategy
18+
import wpimath.units
19+
from photonlibpy import PhotonCamera, PhotonPoseEstimator, PoseStrategy
20+
from photonlibpy.estimation import TargetModel
21+
from photonlibpy.simulation import PhotonCameraSim, SimCameraProperties, VisionTargetSim
1922
from photonlibpy.targeting import (
2023
PhotonPipelineMetadata,
2124
PhotonTrackedTarget,
@@ -27,14 +30,17 @@
2730
from wpimath.geometry import Pose3d, Rotation3d, Transform3d, Translation3d
2831

2932

30-
class PhotonCameraInjector:
33+
class PhotonCameraInjector(PhotonCamera):
3134
result: PhotonPipelineResult
3235

36+
def __init__(self, cameraName="camera"):
37+
super().__init__(cameraName)
38+
3339
def getLatestResult(self) -> PhotonPipelineResult:
3440
return self.result
3541

3642

37-
def setupCommon() -> AprilTagFieldLayout:
43+
def fakeAprilTagFieldLayout() -> AprilTagFieldLayout:
3844
tagList = []
3945
tagPoses = (
4046
Pose3d(3, 3, 3, Rotation3d()),
@@ -53,8 +59,7 @@ def setupCommon() -> AprilTagFieldLayout:
5359

5460

5561
def test_lowestAmbiguityStrategy():
56-
aprilTags = setupCommon()
57-
62+
aprilTags = fakeAprilTagFieldLayout()
5863
cameraOne = PhotonCameraInjector()
5964
cameraOne.result = PhotonPipelineResult(
6065
int(11 * 1e6),
@@ -146,6 +151,86 @@ def test_lowestAmbiguityStrategy():
146151
assertEquals(2, pose.z, 0.01)
147152

148153

154+
def test_pnpDistanceTrigSolve():
155+
aprilTags = fakeAprilTagFieldLayout()
156+
cameraOne = PhotonCameraInjector()
157+
latencySecs: wpimath.units.seconds = 1
158+
fakeTimestampSecs: wpimath.units.seconds = 9 + latencySecs
159+
160+
cameraOneSim = PhotonCameraSim(cameraOne, SimCameraProperties.PERFECT_90DEG())
161+
simTargets = [
162+
VisionTargetSim(tag.pose, TargetModel.AprilTag36h11(), tag.ID)
163+
for tag in aprilTags.getTags()
164+
]
165+
166+
# Compound Rolled + Pitched + Yaw
167+
compoundTestTransform = Transform3d(
168+
-wpimath.units.inchesToMeters(12),
169+
-wpimath.units.inchesToMeters(11),
170+
3,
171+
Rotation3d(
172+
wpimath.units.degreesToRadians(37),
173+
wpimath.units.degreesToRadians(6),
174+
wpimath.units.degreesToRadians(60),
175+
),
176+
)
177+
178+
estimator = PhotonPoseEstimator(
179+
aprilTags,
180+
PoseStrategy.PNP_DISTANCE_TRIG_SOLVE,
181+
cameraOne,
182+
compoundTestTransform,
183+
)
184+
185+
realPose = Pose3d(7.3, 4.42, 0, Rotation3d(0, 0, 2.197)) # Pose to compare with
186+
result = cameraOneSim.process(
187+
latencySecs, realPose.transformBy(estimator.robotToCamera), simTargets
188+
)
189+
bestTarget = result.getBestTarget()
190+
assert bestTarget is not None
191+
assert bestTarget.fiducialId == 0
192+
assert result.ntReceiveTimestampMicros > 0
193+
# Make test independent of the FPGA time.
194+
result.ntReceiveTimestampMicros = fakeTimestampSecs * 1e6
195+
196+
estimator.addHeadingData(
197+
result.getTimestampSeconds(), realPose.rotation().toRotation2d()
198+
)
199+
estimatedRobotPose = estimator.update(result)
200+
201+
assert estimatedRobotPose is not None
202+
pose = estimatedRobotPose.estimatedPose
203+
assertEquals(realPose.x, pose.x, 0.01)
204+
assertEquals(realPose.y, pose.y, 0.01)
205+
assertEquals(0.0, pose.z, 0.01)
206+
207+
# Straight on
208+
fakeTimestampSecs += 60
209+
straightOnTestTransform = Transform3d(0, 0, 3, Rotation3d())
210+
estimator.robotToCamera = straightOnTestTransform
211+
realPose = Pose3d(4.81, 2.38, 0, Rotation3d(0, 0, 2.818)) # Pose to compare with
212+
result = cameraOneSim.process(
213+
latencySecs, realPose.transformBy(estimator.robotToCamera), simTargets
214+
)
215+
bestTarget = result.getBestTarget()
216+
assert bestTarget is not None
217+
assert bestTarget.fiducialId == 0
218+
assert result.ntReceiveTimestampMicros > 0
219+
# Make test independent of the FPGA time.
220+
result.ntReceiveTimestampMicros = fakeTimestampSecs * 1e6
221+
222+
estimator.addHeadingData(
223+
result.getTimestampSeconds(), realPose.rotation().toRotation2d()
224+
)
225+
estimatedRobotPose = estimator.update(result)
226+
227+
assert estimatedRobotPose is not None
228+
pose = estimatedRobotPose.estimatedPose
229+
assertEquals(realPose.x, pose.x, 0.01)
230+
assertEquals(realPose.y, pose.y, 0.01)
231+
assertEquals(0.0, pose.z, 0.01)
232+
233+
149234
def test_multiTagOnCoprocStrategy():
150235
cameraOne = PhotonCameraInjector()
151236
cameraOne.result = PhotonPipelineResult(
@@ -202,8 +287,7 @@ def test_multiTagOnCoprocStrategy():
202287

203288

204289
def test_cacheIsInvalidated():
205-
aprilTags = setupCommon()
206-
290+
aprilTags = fakeAprilTagFieldLayout()
207291
cameraOne = PhotonCameraInjector()
208292
result = PhotonPipelineResult(
209293
int(20 * 1e6),

0 commit comments

Comments
 (0)