diff --git a/photon-server/src/main/java/org/photonvision/vision/frame/Frame.java b/photon-server/src/main/java/org/photonvision/vision/frame/Frame.java
index 2b47bb169..29899c5a8 100644
--- a/photon-server/src/main/java/org/photonvision/vision/frame/Frame.java
+++ b/photon-server/src/main/java/org/photonvision/vision/frame/Frame.java
@@ -17,7 +17,6 @@
package org.photonvision.vision.frame;
-import edu.wpi.first.wpilibj.geometry.Rotation2d;
import org.opencv.core.Mat;
import org.photonvision.vision.opencv.CVMat;
import org.photonvision.vision.opencv.Releasable;
@@ -37,12 +36,6 @@ public class Frame implements Releasable {
this(image, System.nanoTime(), frameStaticProperties);
}
- public Frame() {
- timestampNanos = 0;
- image = new CVMat(new Mat());
- frameStaticProperties = new FrameStaticProperties(0, 0, 0, new Rotation2d(), null);
- }
-
public void copyTo(Frame destFrame) {
image.getMat().copyTo(destFrame.image.getMat());
}
diff --git a/photon-server/src/main/java/org/photonvision/vision/pipeline/AdvancedPipelineSettings.java b/photon-server/src/main/java/org/photonvision/vision/pipeline/AdvancedPipelineSettings.java
index 061645fb9..375adae60 100644
--- a/photon-server/src/main/java/org/photonvision/vision/pipeline/AdvancedPipelineSettings.java
+++ b/photon-server/src/main/java/org/photonvision/vision/pipeline/AdvancedPipelineSettings.java
@@ -21,12 +21,8 @@ import java.util.Objects;
import org.opencv.core.Point;
import org.photonvision.common.util.numbers.DoubleCouple;
import org.photonvision.common.util.numbers.IntegerCouple;
-import org.photonvision.vision.opencv.ContourGroupingMode;
-import org.photonvision.vision.opencv.ContourIntersectionDirection;
import org.photonvision.vision.opencv.ContourSortMode;
-import org.photonvision.vision.pipe.impl.CornerDetectionPipe;
import org.photonvision.vision.target.RobotOffsetPointMode;
-import org.photonvision.vision.target.TargetModel;
import org.photonvision.vision.target.TargetOffsetPointEdge;
import org.photonvision.vision.target.TargetOrientation;
@@ -75,28 +71,10 @@ public class AdvancedPipelineSettings extends CVPipelineSettings {
public Point offsetDualPointB = new Point();
public double offsetDualPointBArea = 0;
- // how many contours to attempt to group (Single, Dual)
- public ContourGroupingMode contourGroupingMode = ContourGroupingMode.Single;
-
- // the direction in which contours must intersect to be considered intersecting
- public ContourIntersectionDirection contourIntersection = ContourIntersectionDirection.Up;
-
- // 3d settings
- public boolean solvePNPEnabled = false;
- public TargetModel targetModel = TargetModel.get2020Target();
-
- // Corner detection settings
- public CornerDetectionPipe.DetectionStrategy cornerDetectionStrategy =
- CornerDetectionPipe.DetectionStrategy.APPROX_POLY_DP_AND_EXTREME_CORNERS;
- public boolean cornerDetectionUseConvexHulls = true;
- public boolean cornerDetectionExactSideCount = false;
- public int cornerDetectionSideCount = 4;
- public double cornerDetectionAccuracyPercentage = 10;
-
@Override
public boolean equals(Object o) {
if (this == o) return true;
- if (!(o instanceof AdvancedPipelineSettings)) return false;
+ if (o == null || getClass() != o.getClass()) return false;
if (!super.equals(o)) return false;
AdvancedPipelineSettings that = (AdvancedPipelineSettings) o;
return outputShouldDraw == that.outputShouldDraw
@@ -104,31 +82,23 @@ public class AdvancedPipelineSettings extends CVPipelineSettings {
&& erode == that.erode
&& dilate == that.dilate
&& contourSpecklePercentage == that.contourSpecklePercentage
+ && Double.compare(that.offsetDualPointA.x, offsetDualPointA.x) == 0
+ && Double.compare(that.offsetDualPointA.y, offsetDualPointA.y) == 0
&& Double.compare(that.offsetDualPointAArea, offsetDualPointAArea) == 0
+ && Double.compare(that.offsetDualPointB.x, offsetDualPointB.x) == 0
+ && Double.compare(that.offsetDualPointB.y, offsetDualPointB.y) == 0
&& Double.compare(that.offsetDualPointBArea, offsetDualPointBArea) == 0
- && solvePNPEnabled == that.solvePNPEnabled
- && cornerDetectionUseConvexHulls == that.cornerDetectionUseConvexHulls
- && cornerDetectionExactSideCount == that.cornerDetectionExactSideCount
- && cornerDetectionSideCount == that.cornerDetectionSideCount
- && Double.compare(that.cornerDetectionAccuracyPercentage, cornerDetectionAccuracyPercentage)
- == 0
- && Objects.equals(hsvHue, that.hsvHue)
- && Objects.equals(hsvSaturation, that.hsvSaturation)
- && Objects.equals(hsvValue, that.hsvValue)
- && Objects.equals(contourArea, that.contourArea)
- && Objects.equals(contourRatio, that.contourRatio)
- && Objects.equals(contourFullness, that.contourFullness)
+ && hsvHue.equals(that.hsvHue)
+ && hsvSaturation.equals(that.hsvSaturation)
+ && hsvValue.equals(that.hsvValue)
+ && contourArea.equals(that.contourArea)
+ && contourRatio.equals(that.contourRatio)
+ && contourFullness.equals(that.contourFullness)
&& contourSortMode == that.contourSortMode
&& contourTargetOffsetPointEdge == that.contourTargetOffsetPointEdge
&& contourTargetOrientation == that.contourTargetOrientation
&& offsetRobotOffsetMode == that.offsetRobotOffsetMode
- && Objects.equals(offsetSinglePoint, that.offsetSinglePoint)
- && Objects.equals(offsetDualPointA, that.offsetDualPointA)
- && Objects.equals(offsetDualPointB, that.offsetDualPointB)
- && contourGroupingMode == that.contourGroupingMode
- && contourIntersection == that.contourIntersection
- && Objects.equals(targetModel, that.targetModel)
- && cornerDetectionStrategy == that.cornerDetectionStrategy;
+ && offsetSinglePoint.equals(that.offsetSinglePoint);
}
@Override
@@ -154,15 +124,6 @@ public class AdvancedPipelineSettings extends CVPipelineSettings {
offsetDualPointA,
offsetDualPointAArea,
offsetDualPointB,
- offsetDualPointBArea,
- contourGroupingMode,
- contourIntersection,
- solvePNPEnabled,
- targetModel,
- cornerDetectionStrategy,
- cornerDetectionUseConvexHulls,
- cornerDetectionExactSideCount,
- cornerDetectionSideCount,
- cornerDetectionAccuracyPercentage);
+ offsetDualPointBArea);
}
}
diff --git a/photon-server/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipeline.java b/photon-server/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipeline.java
index 1c57739e9..dce29cbc8 100644
--- a/photon-server/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipeline.java
+++ b/photon-server/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipeline.java
@@ -158,9 +158,7 @@ public class ColoredShapePipeline
var solvePNPParams =
new SolvePNPPipe.SolvePNPPipeParams(
- frameStaticProperties.cameraCalibration,
- frameStaticProperties.cameraPitch,
- settings.targetModel);
+ settings.cameraCalibration, settings.cameraPitch, settings.targetModel);
solvePNPPipe.setParams(solvePNPParams);
Draw2dTargetsPipe.Draw2dTargetsParams draw2DTargetsParams =
@@ -180,12 +178,10 @@ public class ColoredShapePipeline
frameStaticProperties);
draw2dCrosshairPipe.setParams(draw2dCrosshairParams);
- var draw3dTargetsParams =
+ var draw3dContoursParams =
new Draw3dTargetsPipe.Draw3dContoursParams(
- settings.outputShouldDraw,
- frameStaticProperties.cameraCalibration,
- settings.targetModel);
- draw3dTargetsPipe.setParams(draw3dTargetsParams);
+ settings.outputShouldDraw, settings.cameraCalibration, settings.targetModel);
+ draw3dTargetsPipe.setParams(draw3dContoursParams);
}
@Override
diff --git a/photon-server/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipelineSettings.java b/photon-server/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipelineSettings.java
index a52d2a47b..e90a4f9a6 100644
--- a/photon-server/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipelineSettings.java
+++ b/photon-server/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipelineSettings.java
@@ -18,8 +18,14 @@
package org.photonvision.vision.pipeline;
import com.fasterxml.jackson.annotation.JsonTypeName;
+import edu.wpi.first.wpilibj.geometry.Rotation2d;
import java.util.Objects;
+import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
+import org.photonvision.vision.opencv.ContourGroupingMode;
+import org.photonvision.vision.opencv.ContourIntersectionDirection;
import org.photonvision.vision.opencv.ContourShape;
+import org.photonvision.vision.pipe.impl.CornerDetectionPipe;
+import org.photonvision.vision.target.TargetModel;
@JsonTypeName("ColoredShapePipelineSettings")
public class ColoredShapePipelineSettings extends AdvancedPipelineSettings {
@@ -36,6 +42,25 @@ public class ColoredShapePipelineSettings extends AdvancedPipelineSettings {
public int minDist = 10;
public int maxCannyThresh = 90;
public int accuracy = 20;
+ // how many contours to attempt to group (Single, Dual)
+ public ContourGroupingMode contourGroupingMode = ContourGroupingMode.Single;
+
+ // the direction in which contours must intersect to be considered intersecting
+ public ContourIntersectionDirection contourIntersection = ContourIntersectionDirection.Up;
+
+ // 3d settings
+ public boolean solvePNPEnabled = false;
+ public CameraCalibrationCoefficients cameraCalibration;
+ public TargetModel targetModel;
+ public Rotation2d cameraPitch = Rotation2d.fromDegrees(0.0); // TODO where should pitch live?
+
+ // Corner detection settings
+ public CornerDetectionPipe.DetectionStrategy cornerDetectionStrategy =
+ CornerDetectionPipe.DetectionStrategy.APPROX_POLY_DP_AND_EXTREME_CORNERS;
+ public boolean cornerDetectionUseConvexHulls = true;
+ public boolean cornerDetectionExactSideCount = false;
+ public int cornerDetectionSideCount = 4;
+ public double cornerDetectionAccuracyPercentage = 10;
public ColoredShapePipelineSettings() {
super();
@@ -45,7 +70,7 @@ public class ColoredShapePipelineSettings extends AdvancedPipelineSettings {
@Override
public boolean equals(Object o) {
if (this == o) return true;
- if (!(o instanceof ColoredShapePipelineSettings)) return false;
+ if (o == null || getClass() != o.getClass()) return false;
if (!super.equals(o)) return false;
ColoredShapePipelineSettings that = (ColoredShapePipelineSettings) o;
return Double.compare(that.minArea, minArea) == 0
@@ -59,7 +84,19 @@ public class ColoredShapePipelineSettings extends AdvancedPipelineSettings {
&& minDist == that.minDist
&& maxCannyThresh == that.maxCannyThresh
&& accuracy == that.accuracy
- && desiredShape == that.desiredShape;
+ && solvePNPEnabled == that.solvePNPEnabled
+ && cornerDetectionUseConvexHulls == that.cornerDetectionUseConvexHulls
+ && cornerDetectionExactSideCount == that.cornerDetectionExactSideCount
+ && cornerDetectionSideCount == that.cornerDetectionSideCount
+ && Double.compare(that.cornerDetectionAccuracyPercentage, cornerDetectionAccuracyPercentage)
+ == 0
+ && desiredShape == that.desiredShape
+ && contourGroupingMode == that.contourGroupingMode
+ && contourIntersection == that.contourIntersection
+ && Objects.equals(cameraCalibration, that.cameraCalibration)
+ && Objects.equals(targetModel, that.targetModel)
+ && Objects.equals(cameraPitch, that.cameraPitch)
+ && cornerDetectionStrategy == that.cornerDetectionStrategy;
}
@Override
@@ -77,6 +114,17 @@ public class ColoredShapePipelineSettings extends AdvancedPipelineSettings {
maxRadius,
minDist,
maxCannyThresh,
- accuracy);
+ accuracy,
+ contourGroupingMode,
+ contourIntersection,
+ solvePNPEnabled,
+ cameraCalibration,
+ targetModel,
+ cameraPitch,
+ cornerDetectionStrategy,
+ cornerDetectionUseConvexHulls,
+ cornerDetectionExactSideCount,
+ cornerDetectionSideCount,
+ cornerDetectionAccuracyPercentage);
}
}
diff --git a/photon-server/src/main/java/org/photonvision/vision/pipeline/OutputStreamPipeline.java b/photon-server/src/main/java/org/photonvision/vision/pipeline/OutputStreamPipeline.java
deleted file mode 100644
index ed93ff6fb..000000000
--- a/photon-server/src/main/java/org/photonvision/vision/pipeline/OutputStreamPipeline.java
+++ /dev/null
@@ -1,130 +0,0 @@
-/*
- * Copyright (C) 2020 Photon Vision.
- *
- * This program is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * This program is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
- */
-
-package org.photonvision.vision.pipeline;
-
-import java.util.List;
-import org.apache.commons.lang3.tuple.Pair;
-import org.apache.commons.lang3.tuple.Triple;
-import org.photonvision.common.util.math.MathUtils;
-import org.photonvision.vision.frame.Frame;
-import org.photonvision.vision.frame.FrameStaticProperties;
-import org.photonvision.vision.opencv.CVMat;
-import org.photonvision.vision.opencv.DualOffsetValues;
-import org.photonvision.vision.pipe.impl.Draw2dCrosshairPipe;
-import org.photonvision.vision.pipe.impl.Draw2dTargetsPipe;
-import org.photonvision.vision.pipe.impl.Draw3dTargetsPipe;
-import org.photonvision.vision.pipe.impl.OutputMatPipe;
-import org.photonvision.vision.pipeline.result.CVPipelineResult;
-import org.photonvision.vision.target.TrackedTarget;
-
-/**
-* This is a "fake" pipeline that is just used to move identical pipe sets out of real pipelines. It
-* shall not get its settings saved, nor shall it be managed by PipelineManager
-*/
-public class OutputStreamPipeline {
-
- private final OutputMatPipe outputMatPipe = new OutputMatPipe();
- private final Draw2dCrosshairPipe draw2dCrosshairPipe = new Draw2dCrosshairPipe();
- private final Draw2dTargetsPipe draw2dTargetsPipe = new Draw2dTargetsPipe();
- private final Draw3dTargetsPipe draw3dTargetsPipe = new Draw3dTargetsPipe();
-
- private final long[] pipeProfileNanos = new long[10];
-
- protected void setPipeParams(
- FrameStaticProperties frameStaticProperties, AdvancedPipelineSettings settings) {
-
- var dualOffsetValues =
- new DualOffsetValues(
- settings.offsetDualPointA,
- settings.offsetDualPointAArea,
- settings.offsetDualPointB,
- settings.offsetDualPointBArea);
-
- var draw2DTargetsParams =
- new Draw2dTargetsPipe.Draw2dTargetsParams(
- settings.outputShouldDraw, settings.outputShowMultipleTargets);
- draw2dTargetsPipe.setParams(draw2DTargetsParams);
-
- var draw2dCrosshairParams =
- new Draw2dCrosshairPipe.Draw2dCrosshairParams(
- settings.outputShouldDraw,
- settings.offsetRobotOffsetMode,
- settings.offsetSinglePoint,
- dualOffsetValues,
- frameStaticProperties);
- draw2dCrosshairPipe.setParams(draw2dCrosshairParams);
-
- var draw3dTargetsParams =
- new Draw3dTargetsPipe.Draw3dContoursParams(
- settings.outputShouldDraw,
- frameStaticProperties.cameraCalibration,
- settings.targetModel);
- draw3dTargetsPipe.setParams(draw3dTargetsParams);
- }
-
- public CVPipelineResult process(
- Frame inputFrame,
- Frame outputFrame,
- AdvancedPipelineSettings settings,
- List targetsToDraw,
- double fpsToDraw) {
- setPipeParams(inputFrame.frameStaticProperties, settings);
- var inMat = inputFrame.image.getMat();
- var outMat = outputFrame.image.getMat();
-
- long sumPipeNanosElapsed = 0L;
-
- // Convert single-channel HSV output mat to 3-channel BGR in preparation for streaming
- var outputMatPipeResult = outputMatPipe.run(outMat);
- sumPipeNanosElapsed += pipeProfileNanos[0] = outputMatPipeResult.nanosElapsed;
-
- // Draw 2D Crosshair on input and output
- var draw2dCrosshairResultOnInput = draw2dCrosshairPipe.run(Pair.of(inMat, targetsToDraw));
- sumPipeNanosElapsed += pipeProfileNanos[1] = draw2dCrosshairResultOnInput.nanosElapsed;
-
- var draw2dCrosshairResultOnOutput = draw2dCrosshairPipe.run(Pair.of(inMat, targetsToDraw));
- sumPipeNanosElapsed += pipeProfileNanos[2] = draw2dCrosshairResultOnOutput.nanosElapsed;
-
- // Draw 2D contours on input and output
- var draw2dTargetsOnInput =
- draw2dTargetsPipe.run(Triple.of(inMat, targetsToDraw, (int) fpsToDraw));
- sumPipeNanosElapsed += pipeProfileNanos[3] = draw2dTargetsOnInput.nanosElapsed;
-
- var draw2dTargetsOnOutput =
- draw2dTargetsPipe.run(Triple.of(outMat, targetsToDraw, (int) fpsToDraw));
- sumPipeNanosElapsed += pipeProfileNanos[4] = draw2dTargetsOnOutput.nanosElapsed;
-
- // Draw 3D Targets on input and output if necessary
- if (settings.solvePNPEnabled) {
- var drawOnInputResult = draw3dTargetsPipe.run(Pair.of(inMat, targetsToDraw));
- sumPipeNanosElapsed += pipeProfileNanos[5] = drawOnInputResult.nanosElapsed;
-
- var drawOnOutputResult = draw3dTargetsPipe.run(Pair.of(outMat, targetsToDraw));
- sumPipeNanosElapsed += pipeProfileNanos[6] = drawOnOutputResult.nanosElapsed;
- } else {
- pipeProfileNanos[5] = 0;
- pipeProfileNanos[6] = 0;
- }
-
- return new CVPipelineResult(
- MathUtils.nanosToMillis(sumPipeNanosElapsed),
- targetsToDraw,
- new Frame(new CVMat(outMat), outputFrame.frameStaticProperties),
- new Frame(new CVMat(inMat), inputFrame.frameStaticProperties));
- }
-}
diff --git a/photon-server/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java b/photon-server/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java
index 04449de2d..a6a073db2 100644
--- a/photon-server/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java
+++ b/photon-server/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java
@@ -18,6 +18,8 @@
package org.photonvision.vision.pipeline;
import java.util.List;
+import org.apache.commons.lang3.tuple.Pair;
+import org.apache.commons.lang3.tuple.Triple;
import org.opencv.core.Mat;
import org.photonvision.common.util.math.MathUtils;
import org.photonvision.vision.frame.Frame;
@@ -46,11 +48,11 @@ public class ReflectivePipeline extends CVPipeline targets, Frame outputFrame) {
diff --git a/photon-server/src/main/java/org/photonvision/vision/processes/VisionModule.java b/photon-server/src/main/java/org/photonvision/vision/processes/VisionModule.java
index 3ae3ffe59..61ab42994 100644
--- a/photon-server/src/main/java/org/photonvision/vision/processes/VisionModule.java
+++ b/photon-server/src/main/java/org/photonvision/vision/processes/VisionModule.java
@@ -37,10 +37,7 @@ import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
import org.photonvision.vision.camera.CameraQuirk;
import org.photonvision.vision.camera.QuirkyCamera;
import org.photonvision.vision.camera.USBCameraSource;
-import org.photonvision.vision.frame.Frame;
import org.photonvision.vision.frame.consumer.MJPGFrameConsumer;
-import org.photonvision.vision.pipeline.AdvancedPipelineSettings;
-import org.photonvision.vision.pipeline.OutputStreamPipeline;
import org.photonvision.vision.pipeline.ReflectivePipelineSettings;
import org.photonvision.vision.pipeline.UICalibrationData;
import org.photonvision.vision.pipeline.result.CVPipelineResult;
@@ -61,7 +58,6 @@ public class VisionModule {
protected final PipelineManager pipelineManager;
protected final VisionSource visionSource;
private final VisionRunner visionRunner;
- private final StreamRunnable streamRunnable;
private final LinkedList resultConsumers = new LinkedList<>();
private final LinkedList fpsLimitedResultConsumers = new LinkedList<>();
private final NTDataPublisher ntConsumer;
@@ -88,7 +84,6 @@ public class VisionModule {
this.visionSource.getFrameProvider(),
this.pipelineManager::getCurrentUserPipeline,
this::consumeResult);
- this.streamRunnable = new StreamRunnable(new OutputStreamPipeline());
this.moduleIndex = index;
// do this
@@ -145,58 +140,6 @@ public class VisionModule {
saveAndBroadcastAll();
}
- private class StreamRunnable extends Thread {
- private final OutputStreamPipeline outputStreamPipeline;
-
- private Frame inputFrame, outputFrame;
- private AdvancedPipelineSettings settings = new AdvancedPipelineSettings();
- private List targets = new ArrayList<>();
- private double fps = 0;
-
- private boolean shouldRun = false;
-
- public StreamRunnable(OutputStreamPipeline outputStreamPipeline) {
- this.outputStreamPipeline = outputStreamPipeline;
- }
-
- public void updateData(
- Frame inputFrame,
- Frame outputFrame,
- AdvancedPipelineSettings settings,
- List targets,
- double fps) {
- this.inputFrame = inputFrame;
- this.outputFrame = outputFrame;
- this.settings = settings;
- this.targets = targets;
- this.fps = fps;
-
- shouldRun =
- inputFrame != null
- && !inputFrame.image.getMat().empty()
- && outputFrame != null
- && !outputFrame.image.getMat().empty();
- }
-
- @Override
- public void run() {
- while (true) {
- if (shouldRun) {
- var osr = outputStreamPipeline.process(inputFrame, outputFrame, settings, targets, fps);
- consumeFpsLimitedResult(osr);
- shouldRun = false;
- } else {
- // busy wait! hurray!
- try {
- Thread.sleep(1);
- } catch (InterruptedException e) {
- e.printStackTrace();
- }
- }
- }
- }
- }
-
void setDriverMode(boolean isDriverMode) {
pipelineManager.setDriverMode(isDriverMode);
setVisionLEDs(!isDriverMode);
@@ -205,7 +148,6 @@ public class VisionModule {
public void start() {
visionRunner.startProcess();
- streamRunnable.start();
}
public void setFovAndPitch(double fov, Rotation2d pitch) {
@@ -405,21 +347,9 @@ public class VisionModule {
private void consumeResult(CVPipelineResult result) {
consumePipelineResult(result);
+ consumeFpsLimitedResult(result);
- // total hack. kms
- if (pipelineManager.getCurrentPipelineIndex() >= 0) {
- var fps = 1000.0 / result.getLatencyMillis();
- streamRunnable.updateData(
- result.inputFrame,
- result.outputFrame,
- (AdvancedPipelineSettings) pipelineManager.getCurrentPipelineSettings(),
- result.targets,
- fps);
- // the streamRunnable manages releasing in this case
- } else {
- consumeFpsLimitedResult(result);
- result.release();
- }
+ result.release();
}
private void consumePipelineResult(CVPipelineResult result) {
@@ -435,7 +365,6 @@ public class VisionModule {
}
lastFrameConsumeMillis = System.currentTimeMillis();
}
- result.release();
}
public void setTargetModel(TargetModel targetModel) {
diff --git a/photon-server/src/test/java/org/photonvision/vision/pipeline/CirclePNPTest.java b/photon-server/src/test/java/org/photonvision/vision/pipeline/CirclePNPTest.java
index bad22ea8b..e62f4e4d4 100644
--- a/photon-server/src/test/java/org/photonvision/vision/pipeline/CirclePNPTest.java
+++ b/photon-server/src/test/java/org/photonvision/vision/pipeline/CirclePNPTest.java
@@ -96,7 +96,9 @@ public class CirclePNPTest {
pipeline.getSettings().solvePNPEnabled = true;
pipeline.getSettings().cornerDetectionAccuracyPercentage = 4;
pipeline.getSettings().cornerDetectionUseConvexHulls = true;
+ pipeline.getSettings().cameraCalibration = getCoeffs(LIFECAM_480P_CAL_FILE);
pipeline.getSettings().targetModel = TargetModel.getCircleTarget(7);
+ pipeline.getSettings().cameraPitch = Rotation2d.fromDegrees(0.0);
pipeline.getSettings().outputShouldDraw = true;
pipeline.getSettings().outputShowMultipleTargets = false;
pipeline.getSettings().contourGroupingMode = ContourGroupingMode.Single;
@@ -109,9 +111,7 @@ public class CirclePNPTest {
var frameProvider =
new FileFrameProvider(
TestUtils.getPowercellImagePath(TestUtils.PowercellTestImages.kPowercell_test_6, false),
- TestUtils.WPI2020Image.FOV,
- new Rotation2d(),
- TestUtils.get2020LifeCamCoeffs(true));
+ TestUtils.WPI2020Image.FOV);
CVPipelineResult pipelineResult = pipeline.run(frameProvider.get());
printTestResults(pipelineResult);