diff --git a/vision/src/main/java/coppercore/vision/CameraIOPhoton.java b/vision/src/main/java/coppercore/vision/CameraIOPhoton.java index 7978692..da313b8 100644 --- a/vision/src/main/java/coppercore/vision/CameraIOPhoton.java +++ b/vision/src/main/java/coppercore/vision/CameraIOPhoton.java @@ -63,7 +63,7 @@ public void updateInputs(CameraIOInputs inputs) { inputs.connected = camera.isConnected(); PhotonPipelineResult result = camera.getLatestResult(); - if (result.getTimestampSeconds() == latestTimestampSeconds) { + if (result.getTimestampSeconds() <= latestTimestampSeconds) { inputs.isNewMeasurement = false; inputs.wasAccepted = false; return;