001/*
002 * Copyright (C) Photon Vision.
003 *
004 * This program is free software: you can redistribute it and/or modify
005 * it under the terms of the GNU General Public License as published by
006 * the Free Software Foundation, either version 3 of the License, or
007 * (at your option) any later version.
008 *
009 * This program is distributed in the hope that it will be useful,
010 * but WITHOUT ANY WARRANTY; without even the implied warranty of
011 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
012 * GNU General Public License for more details.
013 *
014 * You should have received a copy of the GNU General Public License
015 * along with this program.  If not, see <https://www.gnu.org/licenses/>.
016 */
017
018package org.photonvision.vision.pipeline;
019
020import java.util.Objects;
021import org.opencv.core.Point;
022import org.photonvision.common.util.numbers.DoubleCouple;
023import org.photonvision.common.util.numbers.IntegerCouple;
024import org.photonvision.vision.opencv.ContourGroupingMode;
025import org.photonvision.vision.opencv.ContourIntersectionDirection;
026import org.photonvision.vision.opencv.ContourSortMode;
027import org.photonvision.vision.pipe.impl.CornerDetectionPipe;
028import org.photonvision.vision.target.RobotOffsetPointMode;
029import org.photonvision.vision.target.TargetModel;
030import org.photonvision.vision.target.TargetOffsetPointEdge;
031import org.photonvision.vision.target.TargetOrientation;
032
033public class AdvancedPipelineSettings extends CVPipelineSettings {
034    public AdvancedPipelineSettings() {
035        ledMode = true;
036    }
037
038    public IntegerCouple hsvHue = new IntegerCouple(50, 180);
039    public IntegerCouple hsvSaturation = new IntegerCouple(50, 255);
040    public IntegerCouple hsvValue = new IntegerCouple(50, 255);
041    public boolean hueInverted = false;
042
043    public boolean outputShouldDraw = true;
044    public boolean outputShowMultipleTargets = false;
045
046    public DoubleCouple contourArea = new DoubleCouple(0.0, 100.0);
047    public DoubleCouple contourRatio = new DoubleCouple(0.0, 20.0);
048    public DoubleCouple contourFullness = new DoubleCouple(0.0, 100.0);
049    public int contourSpecklePercentage = 5;
050
051    // the order in which to sort contours to find the most desirable
052    public ContourSortMode contourSortMode = ContourSortMode.Largest;
053
054    // the edge (or not) of the target to consider the center point (Top, Bottom, Left, Right,
055    // Center)
056    public TargetOffsetPointEdge contourTargetOffsetPointEdge = TargetOffsetPointEdge.Center;
057
058    // orientation of the target in terms of aspect ratio
059    public TargetOrientation contourTargetOrientation = TargetOrientation.Landscape;
060
061    // the mode in which to offset target center point based on the camera being offset on the
062    // robot
063    // (None, Single Point, Dual Point)
064    public RobotOffsetPointMode offsetRobotOffsetMode = RobotOffsetPointMode.None;
065
066    // the point set by the user in Single Point Offset mode (maybe double too? idr)
067    public Point offsetSinglePoint = new Point();
068
069    // the two values that define the line of the Dual Point Offset calibration (think y=mx+b)
070    public Point offsetDualPointA = new Point();
071    public double offsetDualPointAArea = 0;
072    public Point offsetDualPointB = new Point();
073    public double offsetDualPointBArea = 0;
074
075    // how many contours to attempt to group (Single, Dual)
076    public ContourGroupingMode contourGroupingMode = ContourGroupingMode.Single;
077
078    // the direction in which contours must intersect to be considered intersecting
079    public ContourIntersectionDirection contourIntersection = ContourIntersectionDirection.Up;
080
081    // 3d settings
082    public boolean solvePNPEnabled = false;
083    @SuppressSettingCopy public TargetModel targetModel = TargetModel.k2020HighGoalOuter;
084
085    // Corner detection settings
086    public CornerDetectionPipe.DetectionStrategy cornerDetectionStrategy =
087            CornerDetectionPipe.DetectionStrategy.APPROX_POLY_DP_AND_EXTREME_CORNERS;
088    public boolean cornerDetectionUseConvexHulls = true;
089    public boolean cornerDetectionExactSideCount = false;
090    public int cornerDetectionSideCount = 4;
091    public double cornerDetectionAccuracyPercentage = 10;
092
093    @Override
094    public boolean equals(Object o) {
095        if (this == o) return true;
096        if (!(o instanceof AdvancedPipelineSettings)) return false;
097        if (!super.equals(o)) return false;
098        AdvancedPipelineSettings that = (AdvancedPipelineSettings) o;
099        return outputShouldDraw == that.outputShouldDraw
100                && outputShowMultipleTargets == that.outputShowMultipleTargets
101                && contourSpecklePercentage == that.contourSpecklePercentage
102                && Double.compare(that.offsetDualPointAArea, offsetDualPointAArea) == 0
103                && Double.compare(that.offsetDualPointBArea, offsetDualPointBArea) == 0
104                && solvePNPEnabled == that.solvePNPEnabled
105                && cornerDetectionUseConvexHulls == that.cornerDetectionUseConvexHulls
106                && cornerDetectionExactSideCount == that.cornerDetectionExactSideCount
107                && cornerDetectionSideCount == that.cornerDetectionSideCount
108                && Double.compare(that.cornerDetectionAccuracyPercentage, cornerDetectionAccuracyPercentage)
109                        == 0
110                && Objects.equals(hsvHue, that.hsvHue)
111                && Objects.equals(hsvSaturation, that.hsvSaturation)
112                && Objects.equals(hsvValue, that.hsvValue)
113                && Objects.equals(hueInverted, that.hueInverted)
114                && Objects.equals(contourArea, that.contourArea)
115                && Objects.equals(contourRatio, that.contourRatio)
116                && Objects.equals(contourFullness, that.contourFullness)
117                && contourSortMode == that.contourSortMode
118                && contourTargetOffsetPointEdge == that.contourTargetOffsetPointEdge
119                && contourTargetOrientation == that.contourTargetOrientation
120                && offsetRobotOffsetMode == that.offsetRobotOffsetMode
121                && Objects.equals(offsetSinglePoint, that.offsetSinglePoint)
122                && Objects.equals(offsetDualPointA, that.offsetDualPointA)
123                && Objects.equals(offsetDualPointB, that.offsetDualPointB)
124                && contourGroupingMode == that.contourGroupingMode
125                && contourIntersection == that.contourIntersection
126                && Objects.equals(targetModel, that.targetModel)
127                && cornerDetectionStrategy == that.cornerDetectionStrategy;
128    }
129
130    @Override
131    public int hashCode() {
132        return Objects.hash(
133                super.hashCode(),
134                hsvHue,
135                hsvSaturation,
136                hsvValue,
137                hueInverted,
138                outputShouldDraw,
139                outputShowMultipleTargets,
140                contourArea,
141                contourRatio,
142                contourFullness,
143                contourSpecklePercentage,
144                contourSortMode,
145                contourTargetOffsetPointEdge,
146                contourTargetOrientation,
147                offsetRobotOffsetMode,
148                offsetSinglePoint,
149                offsetDualPointA,
150                offsetDualPointAArea,
151                offsetDualPointB,
152                offsetDualPointBArea,
153                contourGroupingMode,
154                contourIntersection,
155                solvePNPEnabled,
156                targetModel,
157                cornerDetectionStrategy,
158                cornerDetectionUseConvexHulls,
159                cornerDetectionExactSideCount,
160                cornerDetectionSideCount,
161                cornerDetectionAccuracyPercentage);
162    }
163}