diff --git a/photon-client/src/components/dashboard/tabs/InputTab.vue b/photon-client/src/components/dashboard/tabs/InputTab.vue index fe0dc9f34..6e6833080 100644 --- a/photon-client/src/components/dashboard/tabs/InputTab.vue +++ b/photon-client/src/components/dashboard/tabs/InputTab.vue @@ -158,6 +158,16 @@ const interactiveCols = computed(() => (args) => useCameraSettingsStore().changeCurrentPipelineSetting({ cameraWhiteBalanceTemp: args }, false) " /> + , Releasable { /** Ask the camera to rotate frames it outputs */ public abstract void requestHsvSettings(HSVPipe.HSVParams params); + + /** Ask the camera to block for new frames (true) or use latest available (false) */ + public abstract void requestBlockForFrames(boolean blockForFrames); } diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java index 1a9e13e60..8ab83c751 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java @@ -47,6 +47,7 @@ public abstract class CpuImageProcessor extends FrameProvider { private final RotateImagePipe m_rImagePipe = new RotateImagePipe(); private final GrayscalePipe m_grayPipe = new GrayscalePipe(); FrameThresholdType m_processType; + boolean m_blockForFrames = true; private final Object m_mutex = new Object(); @@ -129,4 +130,11 @@ public abstract class CpuImageProcessor extends FrameProvider { public void requestFrameCopies(boolean copyInput, boolean copyOutput) { // We don't actually do zero-copy, so this method is a no-op } + + @Override + public void requestBlockForFrames(boolean blockForFrames) { + synchronized (m_mutex) { + this.m_blockForFrames = blockForFrames; + } + } } diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/LibcameraGpuFrameProvider.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/LibcameraGpuFrameProvider.java index 2fa04fba2..e805602fe 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/provider/LibcameraGpuFrameProvider.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/provider/LibcameraGpuFrameProvider.java @@ -135,6 +135,11 @@ public class LibcameraGpuFrameProvider extends FrameProvider { LibCameraJNI.setFramesToCopy(settables.r_ptr, copyInput, copyOutput); } + @Override + public void requestBlockForFrames(boolean blockForFrames) { + // GPU provider always blocks for frames, so this is a no-op + } + @Override public void release() { synchronized (settables.CAMERA_LOCK) { diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java index 7ec8091a7..85d461ca1 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java @@ -20,11 +20,9 @@ package org.photonvision.vision.frame.provider; import edu.wpi.first.cameraserver.CameraServer; import edu.wpi.first.cscore.CvSink; import edu.wpi.first.cscore.UsbCamera; -import edu.wpi.first.networktables.BooleanSubscriber; import edu.wpi.first.util.PixelFormat; import edu.wpi.first.util.RawFrame; import org.opencv.core.Mat; -import org.photonvision.common.dataflow.networktables.NetworkTablesManager; import org.photonvision.common.logging.LogGroup; import org.photonvision.common.logging.Logger; import org.photonvision.jni.CscoreExtras; @@ -44,9 +42,6 @@ public class USBFrameProvider extends CpuImageProcessor { private long lastTime = 0; - // subscribers are lightweight, and I'm lazy - private final BooleanSubscriber useNewBehaviorSub; - @SuppressWarnings("SpellCheckingInspection") public USBFrameProvider( UsbCamera camera, VisionSourceSettables visionSettables, Runnable connectedCallback) { @@ -59,10 +54,6 @@ public class USBFrameProvider extends CpuImageProcessor { this.settables = visionSettables; - var useNewBehaviorTopic = - NetworkTablesManager.getInstance().kRootTable.getBooleanTopic("use_new_cscore_frametime"); - - useNewBehaviorSub = useNewBehaviorTopic.subscribe(false); this.connectedCallback = connectedCallback; } @@ -86,7 +77,7 @@ public class USBFrameProvider extends CpuImageProcessor { onCameraConnected(); } - if (!useNewBehaviorSub.get()) { + if (m_blockForFrames) { // We allocate memory so we don't fill a Mat in use by another thread (memory model is easier) var mat = new CVMat(); // This is from wpi::Now, or WPIUtilJNI.now(). The epoch from grabFrame is uS since diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java index a512e1fcf..24eea55d9 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java @@ -61,6 +61,8 @@ public class CVPipelineSettings implements Cloneable { public boolean cameraAutoWhiteBalance = false; public double cameraWhiteBalanceTemp = 4000; + public boolean blockForFrames = true; + @Override public boolean equals(Object o) { if (this == o) return true; diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionRunner.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionRunner.java index 46dfcf1c4..fa98fd4be 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionRunner.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionRunner.java @@ -181,6 +181,7 @@ public class VisionRunner { } frameSupplier.requestFrameRotation(settings.inputImageRotationMode); frameSupplier.requestFrameCopies(settings.inputShouldShow, settings.outputShouldShow); + frameSupplier.requestBlockForFrames(settings.blockForFrames); // Grab the new camera frame var frame = frameSupplier.get(); diff --git a/photon-lib/src/main/java/org/photonvision/EstimatedRobotPose.java b/photon-lib/src/main/java/org/photonvision/EstimatedRobotPose.java index 3a4a5209d..1cc55c19d 100644 --- a/photon-lib/src/main/java/org/photonvision/EstimatedRobotPose.java +++ b/photon-lib/src/main/java/org/photonvision/EstimatedRobotPose.java @@ -49,7 +49,6 @@ public class EstimatedRobotPose { * @param estimatedPose estimated pose * @param timestampSeconds timestamp of the estimate * @param targetsUsed list of targets used - * @param strategy pose strategy */ public EstimatedRobotPose( Pose3d estimatedPose, double timestampSeconds, List targetsUsed) {