Skip to content

Commit e6f958d

Browse files
committed
Remove custom corner refinement
1 parent 4a42ebd commit e6f958d

File tree

6 files changed

+7
-114
lines changed

6 files changed

+7
-114
lines changed

photon-client/src/components/dashboard/tabs/ArucoTab.vue

Lines changed: 0 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -65,15 +65,6 @@ const interactiveCols = computed(() =>
6565
(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ threshConstant: value }, false)
6666
"
6767
/>
68-
<pv-switch
69-
v-model="currentPipelineSettings.useCornerRefinement"
70-
label="Refine Corners"
71-
tooltip="Further refine the initial corners with subpixel accuracy."
72-
:switch-cols="interactiveCols"
73-
@update:modelValue="
74-
(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ useCornerRefinement: value }, false)
75-
"
76-
/>
7768
<pv-switch
7869
v-model="currentPipelineSettings.debugThreshold"
7970
label="Debug Threshold"

photon-core/src/main/java/org/photonvision/vision/pipe/impl/ArucoDetectionPipe.java

Lines changed: 2 additions & 65 deletions
Original file line numberDiff line numberDiff line change
@@ -19,12 +19,6 @@
1919

2020
import java.util.List;
2121
import org.opencv.core.Mat;
22-
import org.opencv.core.MatOfPoint2f;
23-
import org.opencv.core.Point;
24-
import org.opencv.core.Scalar;
25-
import org.opencv.core.Size;
26-
import org.opencv.core.TermCriteria;
27-
import org.opencv.imgproc.Imgproc;
2822
import org.photonvision.jni.ArucoNanoV5Detector;
2923
import org.photonvision.jni.ArucoNanoV5Detector.DetectionResult;
3024
import org.photonvision.vision.aruco.ArucoDetectionResult;
@@ -35,12 +29,6 @@
3529
public class ArucoDetectionPipe
3630
extends CVPipe<CVMat, List<ArucoDetectionResult>, ArucoDetectionPipeParams>
3731
implements Releasable {
38-
39-
// Ratio multiplied with image size and added to refinement window size
40-
private static final double kRefineWindowImageRatio = 0.004;
41-
// Ratio multiplied with max marker diagonal length and added to refinement window size
42-
private static final double kRefineWindowMarkerRatio = 0.03;
43-
4432
@Override
4533
protected List<ArucoDetectionResult> process(CVMat in) {
4634
var imgMat = in.getMat();
@@ -50,64 +38,14 @@ protected List<ArucoDetectionResult> process(CVMat in) {
5038
// give up is best we can do here
5139
return List.of();
5240
}
53-
54-
var detections = detect(imgMat);
55-
// manually do corner refinement ourselves
56-
if (params.useCornerRefinement) {
57-
for (var detection : detections) {
58-
double[] xCorners = detection.getXCorners();
59-
double[] yCorners = detection.getYCorners();
60-
Point[] cornerPoints = {
61-
new Point(xCorners[0], yCorners[0]),
62-
new Point(xCorners[1], yCorners[1]),
63-
new Point(xCorners[2], yCorners[2]),
64-
new Point(xCorners[3], yCorners[3])
65-
};
66-
double bltr =
67-
Math.hypot(
68-
cornerPoints[2].x - cornerPoints[0].x, cornerPoints[2].y - cornerPoints[0].y);
69-
double brtl =
70-
Math.hypot(
71-
cornerPoints[3].x - cornerPoints[1].x, cornerPoints[3].y - cornerPoints[1].y);
72-
double minDiag = Math.min(bltr, brtl);
73-
int halfWindowLength =
74-
(int) Math.ceil(kRefineWindowImageRatio * Math.min(imgMat.rows(), imgMat.cols()));
75-
halfWindowLength += (int) (minDiag * kRefineWindowMarkerRatio);
76-
// dont do refinement on small markers
77-
if (halfWindowLength < 4) continue;
78-
var halfWindowSize = new Size(halfWindowLength, halfWindowLength);
79-
var ptsMat = new MatOfPoint2f(cornerPoints);
80-
var criteria =
81-
new TermCriteria(3, params.refinementMaxIterations, params.refinementMinErrorPx);
82-
Imgproc.cornerSubPix(imgMat, ptsMat, halfWindowSize, new Size(-1, -1), criteria);
83-
cornerPoints = ptsMat.toArray();
84-
for (int i = 0; i < cornerPoints.length; i++) {
85-
var pt = cornerPoints[i];
86-
xCorners[i] = pt.x;
87-
yCorners[i] = pt.y;
88-
// If we want to debug the refinement window, draw a rectangle on the image
89-
if (params.debugRefineWindow) {
90-
drawCornerRefineWindow(imgMat, pt, halfWindowLength);
91-
}
92-
}
93-
}
94-
}
95-
return detections;
41+
return detect(imgMat);
9642
}
9743

9844
@Override
9945
public void setParams(ArucoDetectionPipeParams newParams) {
10046
super.setParams(newParams);
10147
}
10248

103-
104-
private void drawCornerRefineWindow(Mat outputMat, Point corner, int windowSize) {
105-
int thickness = (int) (Math.ceil(Math.max(outputMat.cols(), outputMat.rows()) * 0.003));
106-
var pt1 = new Point(corner.x - windowSize, corner.y - windowSize);
107-
var pt2 = new Point(corner.x + windowSize, corner.y + windowSize);
108-
Imgproc.rectangle(outputMat, pt1, pt2, new Scalar(0, 0, 255), thickness);
109-
}
110-
11149
public static List<ArucoDetectionResult> detect(Mat in) {
11250
DetectionResult[] ret = ArucoNanoV5Detector.detect(in);
11351

@@ -117,6 +55,5 @@ public static List<ArucoDetectionResult> detect(Mat in) {
11755
}
11856

11957
@Override
120-
public void release() {
121-
}
58+
public void release() {}
12259
}

photon-core/src/main/java/org/photonvision/vision/pipe/impl/ArucoDetectionPipeParams.java

Lines changed: 2 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -30,22 +30,6 @@ public class ArucoDetectionPipeParams {
3030
public int threshMaxSize = 91;
3131
public double threshConstant = 10;
3232

33-
/**
34-
* If obtained corners should be iteratively refined. This should always be on for 3D estimation.
35-
*/
36-
public boolean useCornerRefinement = true;
37-
38-
/** Maximum corner refinement iterations. */
39-
public int refinementMaxIterations = 30;
40-
41-
/**
42-
* Minimum error (accuracy) for corner refinement in pixels. When a corner refinement iteration
43-
* moves the corner by less than this value, the refinement is considered finished.
44-
*/
45-
public double refinementMinErrorPx = 0.005;
46-
47-
public boolean debugRefineWindow = false;
48-
4933
@Override
5034
public boolean equals(Object o) {
5135
if (this == o) return true;
@@ -55,22 +39,11 @@ public boolean equals(Object o) {
5539
&& threshMinSize == that.threshMinSize
5640
&& threshStepSize == that.threshStepSize
5741
&& threshMaxSize == that.threshMaxSize
58-
&& threshConstant == that.threshConstant
59-
&& useCornerRefinement == that.useCornerRefinement
60-
&& refinementMaxIterations == that.refinementMaxIterations
61-
&& refinementMinErrorPx == that.refinementMinErrorPx;
42+
&& threshConstant == that.threshConstant;
6243
}
6344

6445
@Override
6546
public int hashCode() {
66-
return Objects.hash(
67-
tagFamily,
68-
threshMinSize,
69-
threshStepSize,
70-
threshMaxSize,
71-
threshConstant,
72-
useCornerRefinement,
73-
refinementMaxIterations,
74-
refinementMinErrorPx);
47+
return Objects.hash(tagFamily, threshMinSize, threshStepSize, threshMaxSize, threshConstant);
7548
}
7649
}

photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipeline.java

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -96,9 +96,6 @@ protected void setPipeParamsImpl() {
9696
params.threshMaxSize = threshMaxSize;
9797
params.threshConstant = settings.threshConstant;
9898

99-
params.useCornerRefinement = settings.useCornerRefinement;
100-
params.refinementMaxIterations = settings.refineNumIterations;
101-
params.refinementMinErrorPx = settings.refineMinErrorPx;
10299
arucoDetectionPipe.setParams(params);
103100

104101
if (frameStaticProperties.cameraCalibration != null) {

photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipelineSettings.java

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -30,11 +30,6 @@ public class ArucoPipelineSettings extends AdvancedPipelineSettings {
3030
public int threshStepSize = 40;
3131
public double threshConstant = 10;
3232
public boolean debugThreshold = false;
33-
34-
public boolean useCornerRefinement = true;
35-
public int refineNumIterations = 30;
36-
public double refineMinErrorPx = 0.005;
37-
3833
public boolean doMultiTarget = false;
3934
public boolean doSingleTargetAlways = false;
4035

photon-core/src/test/java/org/photonvision/vision/pipeline/ArucoPipelineTest.java

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -19,9 +19,8 @@
1919

2020
import static org.junit.jupiter.api.Assertions.assertEquals;
2121

22-
import java.io.IOException;
23-
2422
import edu.wpi.first.math.geometry.Translation3d;
23+
import java.io.IOException;
2524
import org.junit.jupiter.api.BeforeEach;
2625
import org.junit.jupiter.api.Test;
2726
import org.photonvision.common.configuration.ConfigManager;
@@ -55,7 +54,8 @@ public void testApriltagFacingCamera() {
5554

5655
var frameProvider =
5756
new FileFrameProvider(
58-
TestUtils.getTestImagesPath(false).resolve(TestUtils.WPI2024Images.kSpeakerCenter_143in.path),
57+
TestUtils.getTestImagesPath(false)
58+
.resolve(TestUtils.WPI2024Images.kSpeakerCenter_143in.path),
5959
TestUtils.WPI2024Images.FOV,
6060
TestUtils.get2023LifeCamCoeffs(true));
6161
frameProvider.requestFrameThresholdType(pipeline.getThresholdType());

0 commit comments

Comments
 (0)