diff --git a/photon-server/src/main/java/org/photonvision/vision/pipe/ImageFlipMode.java b/photon-server/src/main/java/org/photonvision/vision/opencv/ImageFlipMode.java similarity index 95% rename from photon-server/src/main/java/org/photonvision/vision/pipe/ImageFlipMode.java rename to photon-server/src/main/java/org/photonvision/vision/opencv/ImageFlipMode.java index 1d0325e1e..a5c09fa96 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipe/ImageFlipMode.java +++ b/photon-server/src/main/java/org/photonvision/vision/opencv/ImageFlipMode.java @@ -15,7 +15,7 @@ * along with this program. If not, see . */ -package org.photonvision.vision.pipe; +package org.photonvision.vision.opencv; public enum ImageFlipMode { NONE(Integer.MIN_VALUE), diff --git a/photon-server/src/main/java/org/photonvision/vision/pipe/ImageRotationMode.java b/photon-server/src/main/java/org/photonvision/vision/opencv/ImageRotationMode.java similarity index 96% rename from photon-server/src/main/java/org/photonvision/vision/pipe/ImageRotationMode.java rename to photon-server/src/main/java/org/photonvision/vision/opencv/ImageRotationMode.java index 88c67bf8a..e3e08a659 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipe/ImageRotationMode.java +++ b/photon-server/src/main/java/org/photonvision/vision/opencv/ImageRotationMode.java @@ -15,7 +15,7 @@ * along with this program. If not, see . */ -package org.photonvision.vision.pipe; +package org.photonvision.vision.opencv; public enum ImageRotationMode { DEG_0(-1), diff --git a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/BlurPipe.java b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/BlurPipe.java index 35b2e3f83..115218739 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/BlurPipe.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/BlurPipe.java @@ -25,7 +25,7 @@ import org.photonvision.vision.pipe.CVPipe; /** Represents a pipeline that blurs the image. */ public class BlurPipe extends CVPipe { /** - * Processes thos pipe. + * Processes this pipe. * * @param in Input for pipe processing. * @return The processed frame. @@ -41,7 +41,7 @@ public class BlurPipe extends CVPipe { public static BlurParams DEFAULT = new BlurParams(0); // Member to store the blur size. - private int m_blurSize; + private final int m_blurSize; /** * Constructs a new BlurImageParams. diff --git a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/Collect2dTargetsPipe.java b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/Collect2dTargetsPipe.java index 0c4340fa3..177ac5328 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/Collect2dTargetsPipe.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/Collect2dTargetsPipe.java @@ -60,22 +60,23 @@ public class Collect2dTargetsPipe } public static class Collect2dTargetsParams { - private FrameStaticProperties m_captureStaticProperties; - private RobotOffsetPointMode m_offsetMode; - private double m_calibrationM, m_calibrationB; - private Point m_userOffsetPoint; - private TargetOffsetPointEdge m_region; - private TargetOrientation m_orientation; + private final FrameStaticProperties m_frameStaticProperties; + private final RobotOffsetPointMode m_offsetMode; + private final double m_calibrationM; + private final double m_calibrationB; + private final Point m_userOffsetPoint; + private final TargetOffsetPointEdge m_region; + private final TargetOrientation m_orientation; public Collect2dTargetsParams( - FrameStaticProperties captureStaticProperties, + FrameStaticProperties frameStaticProperties, RobotOffsetPointMode offsetMode, double calibrationM, double calibrationB, Point calibrationPoint, TargetOffsetPointEdge region, TargetOrientation orientation) { - m_captureStaticProperties = captureStaticProperties; + m_frameStaticProperties = frameStaticProperties; m_offsetMode = offsetMode; m_calibrationM = calibrationM; m_calibrationB = calibrationB; @@ -85,7 +86,7 @@ public class Collect2dTargetsPipe } public FrameStaticProperties getFrameStaticProperties() { - return m_captureStaticProperties; + return m_frameStaticProperties; } public RobotOffsetPointMode getOffsetMode() { diff --git a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/Draw2dCrosshairPipe.java b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/Draw2dCrosshairPipe.java index d29462f13..740b4ef24 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/Draw2dCrosshairPipe.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/Draw2dCrosshairPipe.java @@ -65,10 +65,10 @@ public class Draw2dCrosshairPipe } public static class Draw2dCrosshairParams { - private RobotOffsetPointMode m_calibrationMode; - private DoubleCouple m_calibrationPoint; - public boolean m_showCrosshair = true; - public Color m_crosshairColor = Color.GREEN; + private final RobotOffsetPointMode m_calibrationMode; + private final DoubleCouple m_calibrationPoint; + private final boolean m_showCrosshair = true; + private final Color m_crosshairColor = Color.GREEN; public Draw2dCrosshairParams( RobotOffsetPointMode calibrationMode, DoubleCouple calibrationPoint) { diff --git a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/Draw2dContoursPipe.java b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/Draw2dTargetsPipe.java similarity index 97% rename from photon-server/src/main/java/org/photonvision/vision/pipe/impl/Draw2dContoursPipe.java rename to photon-server/src/main/java/org/photonvision/vision/pipe/impl/Draw2dTargetsPipe.java index 8dc57431d..9cf21f1ec 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/Draw2dContoursPipe.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/Draw2dTargetsPipe.java @@ -27,8 +27,8 @@ import org.photonvision.common.util.ColorHelper; import org.photonvision.vision.pipe.CVPipe; import org.photonvision.vision.target.TrackedTarget; -public class Draw2dContoursPipe - extends CVPipe>, Mat, Draw2dContoursPipe.Draw2dContoursParams> { +public class Draw2dTargetsPipe + extends CVPipe>, Mat, Draw2dTargetsPipe.Draw2dContoursParams> { private List m_drawnContours = new ArrayList<>(); @@ -101,7 +101,7 @@ public class Draw2dContoursPipe public static class Draw2dContoursParams { public boolean showCentroid = true; - public boolean showMultiple = true; + public boolean showMultiple; public int boxOutlineSize = 1; public boolean showRotatedBox = true; public boolean showShape = false; diff --git a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/ErodeDilatePipe.java b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/ErodeDilatePipe.java index 96545be21..b11ba1724 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/ErodeDilatePipe.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/ErodeDilatePipe.java @@ -35,9 +35,9 @@ public class ErodeDilatePipe extends CVPipe process(List in) { m_filteredContours.clear(); for (Contour contour : in) { - try { - filterContour(contour); - } catch (Exception e) { - System.err.println("An error occurred while filtering contours."); - e.printStackTrace(); - } + filterContour(contour); } return m_filteredContours; } @@ -49,15 +44,15 @@ public class FilterContoursPipe private void filterContour(Contour contour) { // Area Filtering. double contourArea = contour.getArea(); - double areaRatio = (contourArea / params.getCamProperties().imageArea); + double areaRatio = (contourArea / params.getFrameStaticProperties().imageArea); double minArea = MathUtils.sigmoid(params.getArea().getFirst()); double maxArea = MathUtils.sigmoid(params.getArea().getSecond()); if (areaRatio < minArea || areaRatio > maxArea) return; // Extent Filtering. RotatedRect minAreaRect = contour.getMinAreaRect(); - double minExtent = params.getExtent().getFirst() * minAreaRect.size.area() / 100; - double maxExtent = params.getExtent().getSecond() * minAreaRect.size.area() / 100; + double minExtent = params.getFullness().getFirst() * minAreaRect.size.area() / 100; + double maxExtent = params.getFullness().getSecond() * minAreaRect.size.area() / 100; if (contourArea <= minExtent || contourArea >= maxExtent) return; // Aspect Ratio Filtering. @@ -70,10 +65,10 @@ public class FilterContoursPipe } public static class FilterContoursParams { - private DoubleCouple m_area; - private DoubleCouple m_ratio; - private DoubleCouple m_extent; - private FrameStaticProperties m_camProperties; + private final DoubleCouple m_area; + private final DoubleCouple m_ratio; + private final DoubleCouple m_fullness; + private final FrameStaticProperties m_frameStaticProperties; public FilterContoursParams( DoubleCouple area, @@ -82,8 +77,8 @@ public class FilterContoursPipe FrameStaticProperties camProperties) { this.m_area = area; this.m_ratio = ratio; - this.m_extent = extent; - this.m_camProperties = camProperties; + this.m_fullness = extent; + this.m_frameStaticProperties = camProperties; } public DoubleCouple getArea() { @@ -94,12 +89,12 @@ public class FilterContoursPipe return m_ratio; } - public DoubleCouple getExtent() { - return m_extent; + public DoubleCouple getFullness() { + return m_fullness; } - public FrameStaticProperties getCamProperties() { - return m_camProperties; + public FrameStaticProperties getFrameStaticProperties() { + return m_frameStaticProperties; } } } diff --git a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FilterShapesPipe.java b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FilterShapesPipe.java index e3f02c903..e13abaedc 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FilterShapesPipe.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FilterShapesPipe.java @@ -43,11 +43,11 @@ public class FilterShapesPipe } public static class FilterShapesPipeParams { - ContourShape desiredShape; - double minArea; - double maxArea; - double minPeri; - double maxPeri; + private final ContourShape desiredShape; + private final double minArea; + private final double maxArea; + private final double minPeri; + private final double maxPeri; public FilterShapesPipeParams( ContourShape desiredShape, double minArea, double maxArea, double minPeri, double maxPeri) { diff --git a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java index e72c6b00a..18a304fd8 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java @@ -28,8 +28,8 @@ import org.photonvision.vision.pipe.CVPipe; public class FindBoardCornersPipe extends CVPipe, List>, FindBoardCornersPipe.FindCornersPipeParams> { MatOfPoint3f objectPoints = new MatOfPoint3f(); - private List listOfObjectPoints = new ArrayList<>(); - private List listOfImagePoints = new ArrayList<>(); + private final List listOfObjectPoints = new ArrayList<>(); + private final List listOfImagePoints = new ArrayList<>(); Size imageSize; Size patternSize; diff --git a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FindCirclesPipe.java b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FindCirclesPipe.java index e22435e78..f05c79767 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FindCirclesPipe.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FindCirclesPipe.java @@ -31,11 +31,8 @@ import org.photonvision.vision.pipe.CVPipe; public class FindCirclesPipe extends CVPipe>, List, FindCirclesPipe.FindCirclePipeParams> { - double[] c; - Mat circles = new Mat(); - Moments mu; - double x_center; - double y_center; + private final Mat circles = new Mat(); + /** * Runs the process for the pipe. * @@ -58,11 +55,12 @@ public class FindCirclesPipe params.minRadius, params.maxRadius); for (int x = 0; x < circles.cols(); x++) { - c = circles.get(0, x); - x_center = c[0]; - y_center = c[1]; + double[] c = circles.get(0, x); + double x_center = c[0]; + double y_center = c[1]; + for (Contour contour : in.getRight()) { - mu = contour.getMoments(); + Moments mu = contour.getMoments(); if (Math.abs(x_center - (mu.m10 / mu.m00)) <= params.allowableThreshold && Math.abs(y_center - (mu.m01 / mu.m00)) <= params.allowableThreshold) { output.add(new CVShape(contour, ContourShape.Circle)); @@ -74,12 +72,12 @@ public class FindCirclesPipe } public static class FindCirclePipeParams { - public int allowableThreshold; - public int minRadius; - public int maxRadius; - public int minDist; - public int maxCannyThresh; - public int accuracy; + private final int allowableThreshold; + private final int minRadius; + private final int maxRadius; + private final int minDist; + private final int maxCannyThresh; + private final int accuracy; public FindCirclePipeParams( int allowableThreshold, diff --git a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FindContoursPipe.java b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FindContoursPipe.java index 7b770e7af..b243f46fa 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FindContoursPipe.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FindContoursPipe.java @@ -29,7 +29,7 @@ import org.photonvision.vision.pipe.CVPipe; public class FindContoursPipe extends CVPipe, FindContoursPipe.FindContoursParams> { - private List m_foundContours = new ArrayList<>(); + private final List m_foundContours = new ArrayList<>(); @Override protected List process(Mat in) { diff --git a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FindPolygonPipe.java b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FindPolygonPipe.java index c3ebfa368..4e8c74876 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FindPolygonPipe.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FindPolygonPipe.java @@ -28,8 +28,7 @@ import org.photonvision.vision.pipe.CVPipe; public class FindPolygonPipe extends CVPipe, List, FindPolygonPipe.FindPolygonPipeParams> { - private int corners; - private MatOfPoint2f approx = new MatOfPoint2f(); + private final MatOfPoint2f approx = new MatOfPoint2f(); /* * Runs the process for the pipe. @@ -49,7 +48,7 @@ public class FindPolygonPipe private CVShape getShape(Contour in) { - corners = getCorners(in); + int corners = getCorners(in); if (ContourShape.fromSides(corners) == null) { return new CVShape(in, ContourShape.Custom); } @@ -76,7 +75,7 @@ public class FindPolygonPipe } public static class FindPolygonPipeParams { - double accuracyPercentage; + private final double accuracyPercentage; public FindPolygonPipeParams(double accuracyPercentage) { this.accuracyPercentage = accuracyPercentage; diff --git a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FindShapesPipe.java b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FindShapesPipe.java deleted file mode 100644 index 0aee87190..000000000 --- a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/FindShapesPipe.java +++ /dev/null @@ -1,58 +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.pipe.impl; - -import java.util.List; -import org.opencv.core.MatOfPoint2f; -import org.opencv.imgproc.Imgproc; -import org.photonvision.vision.opencv.CVShape; -import org.photonvision.vision.opencv.Contour; -import org.photonvision.vision.opencv.ContourShape; -import org.photonvision.vision.pipe.CVPipe; - -public class FindShapesPipe - extends CVPipe, List, FindShapesPipe.FindShapesParams> { - - MatOfPoint2f approxCurve = new MatOfPoint2f(); - - @Override - protected List process(List in) { - approxCurve.release(); - approxCurve = new MatOfPoint2f(); - - for (var contour : in) { - - if (params.desiredShape == ContourShape.Circle) { - - } else { - int desiredSides = params.desiredShape.sides; - Imgproc.approxPolyDP(contour.getMat2f(), approxCurve, params.approxEpsilon, true); - - // int actualSides = approxCurve. - // switch () - System.out.println("fugg"); - } - } - return List.of(); - } - - public static class FindShapesParams { - double approxEpsilon = 0.05; - ContourShape desiredShape; - } -} diff --git a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/GroupContoursPipe.java b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/GroupContoursPipe.java index f7f412edc..a1ace39af 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/GroupContoursPipe.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/GroupContoursPipe.java @@ -29,7 +29,7 @@ import org.photonvision.vision.target.PotentialTarget; public class GroupContoursPipe extends CVPipe, List, GroupContoursPipe.GroupContoursParams> { - private List m_targets = new ArrayList<>(); + private final List m_targets = new ArrayList<>(); @Override protected List process(List input) { @@ -49,19 +49,20 @@ public class GroupContoursPipe if (input.size() > groupingCount) { input.sort(Contour.SortByMomentsX); // also why reverse? shouldn't the sort comparator just get reversed? + // TODO: Matt, see this Collections.reverse(input); - // find out next time on Code Mysteries... for (int i = 0; i < input.size() - 1; i++) { // make a list of the desired count of contours to group List groupingSet; + + // TODO: are these try/catch avoidable? try { groupingSet = input.subList(i, i + groupingCount); } catch (IndexOutOfBoundsException e) { continue; } try { - // FYI: This method only takes 2 contours! Contour groupedContour = Contour.groupContoursByIntersection( @@ -81,8 +82,8 @@ public class GroupContoursPipe } public static class GroupContoursParams { - private ContourGroupingMode m_group; - private ContourIntersectionDirection m_intersection; + private final ContourGroupingMode m_group; + private final ContourIntersectionDirection m_intersection; public GroupContoursParams( ContourGroupingMode group, ContourIntersectionDirection intersectionDirection) { diff --git a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/HSVPipe.java b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/HSVPipe.java index 90813cc2f..d406ad64f 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/HSVPipe.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/HSVPipe.java @@ -18,7 +18,6 @@ package org.photonvision.vision.pipe.impl; import org.opencv.core.Core; -import org.opencv.core.CvException; import org.opencv.core.Mat; import org.opencv.core.Scalar; import org.opencv.imgproc.Imgproc; @@ -27,35 +26,25 @@ import org.photonvision.vision.pipe.CVPipe; public class HSVPipe extends CVPipe { - private Mat m_outputMat = new Mat(); + private final Mat m_outputMat = new Mat(); @Override protected Mat process(Mat in) { in.copyTo(m_outputMat); - try { - Imgproc.cvtColor(m_outputMat, m_outputMat, Imgproc.COLOR_BGR2HSV, 3); - Core.inRange(m_outputMat, params.getHsvLower(), params.getHsvUpper(), m_outputMat); - } catch (CvException e) { - System.err.println("(HSVPipe) Exception thrown by OpenCV: \n" + e.getMessage()); - } - + Imgproc.cvtColor(m_outputMat, m_outputMat, Imgproc.COLOR_BGR2HSV, 3); + Core.inRange(m_outputMat, params.getHsvLower(), params.getHsvUpper(), m_outputMat); return m_outputMat; } public static class HSVParams { - private Scalar m_hsvLower; - private Scalar m_hsvUpper; + private final Scalar m_hsvLower; + private final Scalar m_hsvUpper; public HSVParams(IntegerCouple hue, IntegerCouple saturation, IntegerCouple value) { m_hsvLower = new Scalar(hue.getFirst(), saturation.getFirst(), value.getFirst()); m_hsvUpper = new Scalar(hue.getSecond(), saturation.getSecond(), value.getSecond()); } - public HSVParams(Scalar hsvLower, Scalar hsvUpper) { - m_hsvLower = hsvLower; - m_hsvUpper = hsvUpper; - } - public Scalar getHsvLower() { return m_hsvLower; } diff --git a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/OutputMatPipe.java b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/OutputMatPipe.java index 9f946a1bc..3136dadf1 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/OutputMatPipe.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/OutputMatPipe.java @@ -17,7 +17,6 @@ package org.photonvision.vision.pipe.impl; -import org.opencv.core.CvException; import org.opencv.core.Mat; import org.opencv.imgproc.Imgproc; import org.photonvision.vision.opencv.DualMat; @@ -33,12 +32,8 @@ public class OutputMatPipe extends CVPipe { diff --git a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/SolvePNPPipe.java b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/SolvePNPPipe.java index f03dc7808..6a48afe68 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/SolvePNPPipe.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/SolvePNPPipe.java @@ -35,7 +35,7 @@ import org.photonvision.vision.target.TrackedTarget; public class SolvePNPPipe extends CVPipe, List, SolvePNPPipe.SolvePNPPipeParams> { - private MatOfPoint2f imagePoints = new MatOfPoint2f(); + private final MatOfPoint2f imagePoints = new MatOfPoint2f(); @Override protected List process(List targetList) { @@ -53,7 +53,6 @@ public class SolvePNPPipe || corners.isEmpty() || params.cameraCoefficients.getCameraIntrinsicsMat() == null || params.cameraCoefficients.getCameraExtrinsicsMat() == null) { - targetPose = new Pose2d(); return; } this.imagePoints.fromList(corners); @@ -120,7 +119,6 @@ public class SolvePNPPipe // We have a Z_field (out of the camera projected onto the field), and an X left/right. // so Z_field becomes X, and X becomes Y - //noinspection SuspiciousNameCombination var targetLocation = new Translation2d(zField, -x); return new Pose2d(targetLocation, new Rotation2d(targetRotation)); } @@ -132,6 +130,7 @@ public class SolvePNPPipe * @param factor by how much to scale each element * @return the scaled matrix */ + @SuppressWarnings("SameParameterValue") private static Mat matScale(Mat src, double factor) { Mat dst = new Mat(src.rows(), src.cols(), src.type()); Scalar s = new Scalar(factor); diff --git a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/SortContoursPipe.java b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/SortContoursPipe.java index 085d6fa3b..470ae5700 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/SortContoursPipe.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/SortContoursPipe.java @@ -30,11 +30,15 @@ public class SortContoursPipe extends CVPipe< List, List, SortContoursPipe.SortContoursParams> { - private List m_sortedContours = new ArrayList<>(); + private final List m_sortedContours = new ArrayList<>(); @Override protected List process(List in) { + for (var oldTarget : m_sortedContours) { + oldTarget.release(); + } m_sortedContours.clear(); + if (in.size() > 0) { m_sortedContours.addAll(in); if (params.getSortMode() != ContourSortMode.Centermost) { @@ -55,14 +59,14 @@ public class SortContoursPipe } public static class SortContoursParams { - private ContourSortMode m_sortMode; - private FrameStaticProperties m_camProperties; - private int m_maxTargets; + private final ContourSortMode m_sortMode; + private final FrameStaticProperties m_frameStaticProperties; + private final int m_maxTargets; public SortContoursParams( ContourSortMode sortMode, FrameStaticProperties camProperties, int maxTargets) { m_sortMode = sortMode; - m_camProperties = camProperties; + m_frameStaticProperties = camProperties; m_maxTargets = maxTargets; } @@ -71,7 +75,7 @@ public class SortContoursPipe } public FrameStaticProperties getCamProperties() { - return m_camProperties; + return m_frameStaticProperties; } public int getMaxTargets() { diff --git a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/SpeckleRejectPipe.java b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/SpeckleRejectPipe.java index 4267a177e..8f2a97952 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/SpeckleRejectPipe.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/SpeckleRejectPipe.java @@ -25,7 +25,7 @@ import org.photonvision.vision.pipe.CVPipe; public class SpeckleRejectPipe extends CVPipe, List, SpeckleRejectPipe.SpeckleRejectParams> { - private List m_despeckledContours = new ArrayList<>(); + private final List m_despeckledContours = new ArrayList<>(); @Override protected List process(List in) { @@ -53,7 +53,7 @@ public class SpeckleRejectPipe } public static class SpeckleRejectParams { - private double m_minPercentOfAvg; + private final double m_minPercentOfAvg; public SpeckleRejectParams(double minPercentOfAvg) { m_minPercentOfAvg = minPercentOfAvg; diff --git a/photon-server/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java b/photon-server/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java index cbf6b197a..b8c1629c9 100644 --- a/photon-server/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java +++ b/photon-server/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java @@ -21,8 +21,8 @@ import com.fasterxml.jackson.annotation.JsonSubTypes; import com.fasterxml.jackson.annotation.JsonTypeInfo; import java.util.Objects; import org.photonvision.vision.frame.FrameDivisor; -import org.photonvision.vision.pipe.ImageFlipMode; -import org.photonvision.vision.pipe.ImageRotationMode; +import org.photonvision.vision.opencv.ImageFlipMode; +import org.photonvision.vision.opencv.ImageRotationMode; @JsonTypeInfo( use = JsonTypeInfo.Id.NAME, 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 370d5680d..6bb8146d8 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 @@ -51,7 +51,7 @@ public class ColoredShapePipeline private final CornerDetectionPipe cornerDetectionPipe = new CornerDetectionPipe(); private final SolvePNPPipe solvePNPPipe = new SolvePNPPipe(); private final Draw2dCrosshairPipe draw2dCrosshairPipe = new Draw2dCrosshairPipe(); - private final Draw2dContoursPipe draw2dContoursPipe = new Draw2dContoursPipe(); + private final Draw2dTargetsPipe draw2DTargetsPipe = new Draw2dTargetsPipe(); private final Draw3dTargetsPipe draw3dTargetsPipe = new Draw3dTargetsPipe(); private final Mat rawInputMat = new Mat(); @@ -155,13 +155,13 @@ public class ColoredShapePipeline settings.cameraCalibration, settings.cameraPitch, settings.targetModel); solvePNPPipe.setParams(solvePNPParams); - Draw2dContoursPipe.Draw2dContoursParams draw2dContoursParams = - new Draw2dContoursPipe.Draw2dContoursParams(settings.outputShowMultipleTargets); + Draw2dTargetsPipe.Draw2dContoursParams draw2dContoursParams = + new Draw2dTargetsPipe.Draw2dContoursParams(settings.outputShowMultipleTargets); draw2dContoursParams.showShape = true; draw2dContoursParams.showMaximumBox = false; draw2dContoursParams.showRotatedBox = false; draw2dContoursParams.boxOutlineSize = 2; - draw2dContoursPipe.setParams(draw2dContoursParams); + draw2DTargetsPipe.setParams(draw2dContoursParams); Draw2dCrosshairPipe.Draw2dCrosshairParams draw2dCrosshairParams = new Draw2dCrosshairPipe.Draw2dCrosshairParams( @@ -256,7 +256,7 @@ public class ColoredShapePipeline sumPipeNanosElapsed += draw2dCrosshairResult.nanosElapsed; CVPipeResult draw2dContoursResult = - draw2dContoursPipe.apply( + draw2DTargetsPipe.apply( Pair.of(draw2dCrosshairResult.result, collect2dTargetsResult.result)); sumPipeNanosElapsed += draw2dContoursResult.nanosElapsed; 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 516138206..58973f9ed 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 @@ -29,8 +29,8 @@ import org.photonvision.vision.opencv.DualMat; import org.photonvision.vision.pipe.CVPipeResult; import org.photonvision.vision.pipe.impl.Collect2dTargetsPipe; import org.photonvision.vision.pipe.impl.CornerDetectionPipe; -import org.photonvision.vision.pipe.impl.Draw2dContoursPipe; 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.ErodeDilatePipe; import org.photonvision.vision.pipe.impl.FilterContoursPipe; @@ -62,7 +62,7 @@ public class ReflectivePipeline extends CVPipeline draw2dContoursResult = - draw2dContoursPipe.apply( + draw2DTargetsPipe.apply( Pair.of(draw2dCrosshairResult.result, collect2dTargetsResult.result)); sumPipeNanosElapsed += draw2dContoursResult.nanosElapsed;