Skip to content

Commit ab854e9

Browse files
authored
[photon-lib] Invalidate pose cache when setting referencePose (#2040)
1 parent a930852 commit ab854e9

File tree

8 files changed

+164
-30
lines changed

8 files changed

+164
-30
lines changed

photon-lib/py/buildAndTest.sh

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,13 @@
1+
#!/usr/bin/env bash
2+
3+
set -euo pipefail
4+
cd -- "$(dirname -- "$0")"
5+
16
# Uninstall if it already was installed
27
python3 -m pip uninstall -y photonlibpy
38

49
# Build wheel
10+
python3 -m pip install wheel
511
python3 setup.py bdist_wheel
612

713
# Install whatever wheel was made

photon-lib/py/photonlibpy/photonPoseEstimator.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -229,7 +229,7 @@ def _invalidatePoseCache(self) -> None:
229229
self._poseCacheTimestampSeconds = -1.0
230230

231231
def _checkUpdate(self, oldObj, newObj) -> None:
232-
if oldObj != newObj and oldObj is not None and oldObj is not newObj:
232+
if oldObj != newObj:
233233
self._invalidatePoseCache()
234234

235235
def addHeadingData(

photon-lib/py/test/__init__.py

Whitespace-only changes.

photon-lib/py/test/photonPoseEstimator_test.py

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

18+
from test import testUtil
19+
1820
import wpimath.units
1921
from photonlibpy import PhotonCamera, PhotonPoseEstimator, PoseStrategy
2022
from photonlibpy.estimation import TargetModel
@@ -191,7 +193,7 @@ def test_pnpDistanceTrigSolve():
191193
assert bestTarget.fiducialId == 0
192194
assert result.ntReceiveTimestampMicros > 0
193195
# Make test independent of the FPGA time.
194-
result.ntReceiveTimestampMicros = fakeTimestampSecs * 1e6
196+
result.ntReceiveTimestampMicros = int(fakeTimestampSecs * 1e6)
195197

196198
estimator.addHeadingData(
197199
result.getTimestampSeconds(), realPose.rotation().toRotation2d()
@@ -217,7 +219,7 @@ def test_pnpDistanceTrigSolve():
217219
assert bestTarget.fiducialId == 0
218220
assert result.ntReceiveTimestampMicros > 0
219221
# Make test independent of the FPGA time.
220-
result.ntReceiveTimestampMicros = fakeTimestampSecs * 1e6
222+
result.ntReceiveTimestampMicros = int(fakeTimestampSecs * 1e6)
221223

222224
estimator.addHeadingData(
223225
result.getTimestampSeconds(), realPose.rotation().toRotation2d()
@@ -289,8 +291,36 @@ def test_multiTagOnCoprocStrategy():
289291
def test_cacheIsInvalidated():
290292
aprilTags = fakeAprilTagFieldLayout()
291293
cameraOne = PhotonCameraInjector()
294+
295+
estimator = PhotonPoseEstimator(
296+
aprilTags, PoseStrategy.LOWEST_AMBIGUITY, cameraOne, Transform3d()
297+
)
298+
299+
# Initial state, expect no timestamp.
300+
assertEquals(-1, estimator._poseCacheTimestampSeconds)
301+
302+
# First result is 17s after epoch start.
303+
timestamps = testUtil.PipelineTimestamps(captureTimestampMicros=17_000_000)
304+
latencySecs = timestamps.pipelineLatencySecs()
305+
306+
# No targets, expect empty result
307+
cameraOne.result = PhotonPipelineResult(
308+
timestamps.receiveTimestampMicros(),
309+
metadata=timestamps.toPhotonPipelineMetadata(),
310+
)
311+
estimatedPose = estimator.update()
312+
313+
assert estimatedPose is None
314+
assertEquals(
315+
timestamps.receiveTimestampMicros() * 1e-6 - latencySecs,
316+
estimator._poseCacheTimestampSeconds,
317+
1e-3,
318+
)
319+
320+
# Set actual result
321+
timestamps.incrementTimeMicros(2_500_000)
292322
result = PhotonPipelineResult(
293-
int(20 * 1e6),
323+
timestamps.receiveTimestampMicros(),
294324
[
295325
PhotonTrackedTarget(
296326
3.0,
@@ -315,31 +345,21 @@ def test_cacheIsInvalidated():
315345
0.7,
316346
)
317347
],
318-
metadata=PhotonPipelineMetadata(0, int(2 * 1e3), 0),
319-
)
320-
321-
estimator = PhotonPoseEstimator(
322-
aprilTags, PoseStrategy.LOWEST_AMBIGUITY, cameraOne, Transform3d()
348+
metadata=timestamps.toPhotonPipelineMetadata(),
323349
)
324-
325-
# Empty result, expect empty result
326-
cameraOne.result = PhotonPipelineResult(0)
327-
estimatedPose = estimator.update()
328-
assert estimatedPose is None
329-
330-
# Set actual result
331350
cameraOne.result = result
332351
estimatedPose = estimator.update()
333352
assert estimatedPose is not None
334-
assertEquals(20, estimatedPose.timestampSeconds, 0.01)
335-
assertEquals(20 - 2e-3, estimator._poseCacheTimestampSeconds, 1e-3)
353+
expectedTimestamp = timestamps.receiveTimestampMicros() * 1e-6 - latencySecs
354+
assertEquals(expectedTimestamp, estimatedPose.timestampSeconds, 1e-3)
355+
assertEquals(expectedTimestamp, estimator._poseCacheTimestampSeconds, 1e-3)
336356

337357
# And again -- pose cache should mean this is empty
338358
cameraOne.result = result
339359
estimatedPose = estimator.update()
340360
assert estimatedPose is None
341361
# Expect the old timestamp to still be here
342-
assertEquals(20 - 2e-3, estimator._poseCacheTimestampSeconds, 1e-3)
362+
assertEquals(expectedTimestamp, estimator._poseCacheTimestampSeconds, 1e-3)
343363

344364
# Set new field layout -- right after, the pose cache timestamp should be -1
345365
estimator.fieldTags = AprilTagFieldLayout([AprilTag()], 0, 0)
@@ -350,8 +370,14 @@ def test_cacheIsInvalidated():
350370

351371
assert estimatedPose is not None
352372

353-
assertEquals(20, estimatedPose.timestampSeconds, 0.01)
354-
assertEquals(20 - 2e-3, estimator._poseCacheTimestampSeconds, 1e-3)
373+
assertEquals(expectedTimestamp, estimatedPose.timestampSeconds, 1e-3)
374+
assertEquals(expectedTimestamp, estimator._poseCacheTimestampSeconds, 1e-3)
375+
376+
# Setting a value from None to a non-None should invalidate the cache.
377+
assert estimator.referencePose is None
378+
estimator.referencePose = Pose3d(3, 3, 3, Rotation3d())
379+
380+
assertEquals(-1, estimator._poseCacheTimestampSeconds)
355381

356382

357383
def assertEquals(expected, actual, epsilon=0.0):

photon-lib/py/test/testUtil.py

Lines changed: 65 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,65 @@
1+
"""Test utilities."""
2+
3+
from photonlibpy.targeting import PhotonPipelineMetadata
4+
5+
6+
class InvalidTestDataException(ValueError):
7+
pass
8+
9+
10+
class PipelineTimestamps:
11+
"""Helper class to ensure timestamps are positive."""
12+
13+
def __init__(
14+
self,
15+
*,
16+
captureTimestampMicros: int,
17+
pipelineLatencyMicros=2_000,
18+
receiveLatencyMicros=1_000,
19+
):
20+
if captureTimestampMicros < 0:
21+
raise InvalidTestDataException("captureTimestampMicros cannot be negative")
22+
if pipelineLatencyMicros <= 0:
23+
raise InvalidTestDataException("pipelineLatencyMicros must be positive")
24+
if receiveLatencyMicros < 0:
25+
raise InvalidTestDataException("receiveLatencyMicros cannot be negative")
26+
self._captureTimestampMicros = captureTimestampMicros
27+
self._pipelineLatencyMicros = pipelineLatencyMicros
28+
self._receiveLatencyMicros = receiveLatencyMicros
29+
self._sequenceID = 0
30+
31+
@property
32+
def captureTimestampMicros(self) -> int:
33+
return self._captureTimestampMicros
34+
35+
@captureTimestampMicros.setter
36+
def captureTimestampMicros(self, micros: int) -> None:
37+
if micros < 0:
38+
raise InvalidTestDataException("captureTimestampMicros cannot be negative")
39+
if micros < self._captureTimestampMicros:
40+
raise InvalidTestDataException("time cannot go backwards")
41+
self._captureTimestampMicros = micros
42+
self._sequenceID += 1
43+
44+
@property
45+
def pipelineLatencyMicros(self) -> int:
46+
return self._pipelineLatencyMicros
47+
48+
def pipelineLatencySecs(self) -> float:
49+
return self.pipelineLatencyMicros * 1e-6
50+
51+
def incrementTimeMicros(self, micros: int) -> None:
52+
self.captureTimestampMicros += micros
53+
54+
def publishTimestampMicros(self) -> int:
55+
return self._captureTimestampMicros + self.pipelineLatencyMicros
56+
57+
def receiveTimestampMicros(self) -> int:
58+
return self.publishTimestampMicros() + self._receiveLatencyMicros
59+
60+
def toPhotonPipelineMetadata(self) -> PhotonPipelineMetadata:
61+
return PhotonPipelineMetadata(
62+
captureTimestampMicros=self.captureTimestampMicros,
63+
publishTimestampMicros=self.publishTimestampMicros(),
64+
sequenceID=self._sequenceID,
65+
)

photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java

Lines changed: 2 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -42,11 +42,7 @@
4242
import edu.wpi.first.math.numbers.N3;
4343
import edu.wpi.first.math.numbers.N8;
4444
import edu.wpi.first.wpilibj.DriverStation;
45-
import java.util.ArrayList;
46-
import java.util.HashSet;
47-
import java.util.List;
48-
import java.util.Optional;
49-
import java.util.Set;
45+
import java.util.*;
5046
import org.photonvision.estimation.TargetModel;
5147
import org.photonvision.estimation.VisionEstimation;
5248
import org.photonvision.targeting.PhotonPipelineResult;
@@ -175,7 +171,7 @@ private void invalidatePoseCache() {
175171
}
176172

177173
private void checkUpdate(Object oldObj, Object newObj) {
178-
if (oldObj != newObj && oldObj != null && !oldObj.equals(newObj)) {
174+
if (!Objects.equals(oldObj, newObj)) {
179175
invalidatePoseCache();
180176
}
181177
}

photon-lib/src/test/java/org/photonvision/PhotonPoseEstimatorTest.java

Lines changed: 14 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@
2828
import static org.junit.jupiter.api.Assertions.assertEquals;
2929
import static org.junit.jupiter.api.Assertions.assertFalse;
3030
import static org.junit.jupiter.api.Assertions.assertNotNull;
31+
import static org.junit.jupiter.api.Assertions.assertNull;
3132
import static org.junit.jupiter.api.Assertions.assertTrue;
3233
import static org.junit.jupiter.api.Assertions.fail;
3334

@@ -38,11 +39,13 @@
3839
import edu.wpi.first.math.MatBuilder;
3940
import edu.wpi.first.math.Nat;
4041
import edu.wpi.first.math.VecBuilder;
42+
import edu.wpi.first.math.geometry.Pose2d;
4143
import edu.wpi.first.math.geometry.Pose3d;
4244
import edu.wpi.first.math.geometry.Quaternion;
4345
import edu.wpi.first.math.geometry.Rotation2d;
4446
import edu.wpi.first.math.geometry.Rotation3d;
4547
import edu.wpi.first.math.geometry.Transform3d;
48+
import edu.wpi.first.math.geometry.Translation2d;
4649
import edu.wpi.first.math.geometry.Translation3d;
4750
import edu.wpi.first.math.util.Units;
4851
import java.io.IOException;
@@ -592,8 +595,8 @@ void cacheIsInvalidated() {
592595
var result =
593596
new PhotonPipelineResult(
594597
0,
595-
20000000,
596-
1100000,
598+
20_000_000,
599+
1_100_000,
597600
1024,
598601
List.of(
599602
new PhotonTrackedTarget(
@@ -624,6 +627,9 @@ void cacheIsInvalidated() {
624627
PoseStrategy.AVERAGE_BEST_TARGETS,
625628
new Transform3d(new Translation3d(0, 0, 0), new Rotation3d()));
626629

630+
// Initial state, expect no timestamp
631+
assertEquals(-1, estimator.poseCacheTimestampSeconds);
632+
627633
// Empty result, expect empty result
628634
cameraOne.result = new PhotonPipelineResult();
629635
cameraOne.result.metadata.captureTimestampMicros = (long) (1 * 1e6);
@@ -652,6 +658,12 @@ void cacheIsInvalidated() {
652658
estimatedPose = estimator.update(cameraOne.result);
653659
assertEquals(20, estimatedPose.get().timestampSeconds, .01);
654660
assertEquals(20, estimator.poseCacheTimestampSeconds);
661+
662+
// Setting a value from None to a non-None should invalidate the cache
663+
assertNull(estimator.getReferencePose());
664+
assertEquals(20, estimator.poseCacheTimestampSeconds);
665+
estimator.setReferencePose(new Pose2d(new Translation2d(1, 2), Rotation2d.kZero));
666+
assertEquals(-1, estimator.poseCacheTimestampSeconds, "wtf");
655667
}
656668

657669
@Test

photon-lib/src/test/native/cpp/PhotonPoseEstimatorTest.cpp

Lines changed: 30 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -412,12 +412,41 @@ TEST(PhotonPoseEstimatorTest, PoseCache) {
412412
EXPECT_NEAR((15_s - 3_ms).to<double>(),
413413
estimatedPose.value().timestamp.to<double>(), 1e-6);
414414

415-
// And again -- now pose cache should be empty
415+
// And again -- pose cache should result in returning std::nullopt
416416
for (const auto& result : cameraOne.GetAllUnreadResults()) {
417417
estimatedPose = estimator.Update(result);
418418
}
419419

420420
EXPECT_FALSE(estimatedPose);
421+
422+
// If the camera produces a result that is > 1 micro second later,
423+
// the pose cache should not be hit.
424+
cameraOne.testResult[0].SetReceiveTimestamp(units::second_t(16));
425+
for (const auto& result : cameraOne.GetAllUnreadResults()) {
426+
estimatedPose = estimator.Update(result);
427+
}
428+
429+
EXPECT_NEAR((16_s - 3_ms).to<double>(),
430+
estimatedPose.value().timestamp.to<double>(), 1e-6);
431+
432+
// And again -- pose cache should result in returning std::nullopt
433+
for (const auto& result : cameraOne.GetAllUnreadResults()) {
434+
estimatedPose = estimator.Update(result);
435+
}
436+
437+
EXPECT_FALSE(estimatedPose);
438+
439+
// Setting ReferencePose should also clear the cache
440+
estimator.SetReferencePose(frc::Pose3d(units::meter_t(1), units::meter_t(2),
441+
units::meter_t(3), frc::Rotation3d()));
442+
443+
for (const auto& result : cameraOne.GetAllUnreadResults()) {
444+
estimatedPose = estimator.Update(result);
445+
}
446+
447+
ASSERT_TRUE(estimatedPose);
448+
EXPECT_NEAR((16_s - 3_ms).to<double>(),
449+
estimatedPose.value().timestamp.to<double>(), 1e-6);
421450
}
422451

423452
TEST(PhotonPoseEstimatorTest, MultiTagOnRioFallback) {

0 commit comments

Comments
 (0)