Skip to content

Commit

Permalink
more parameter testing
Browse files Browse the repository at this point in the history
  • Loading branch information
amquake committed Oct 10, 2023
1 parent fa930b8 commit 9ecac48
Show file tree
Hide file tree
Showing 8 changed files with 172 additions and 139 deletions.
76 changes: 15 additions & 61 deletions photon-client/src/components/dashboard/tabs/ArucoTab.vue
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,8 @@ const interactiveCols = computed(
label="Thresh Min Size"
tooltip=""
:min="3"
:max="128"
:step="1"
:max="255"
:step="2"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ threshMinSize: value }, false)"
/>
<cv-slider
Expand All @@ -38,7 +38,7 @@ const interactiveCols = computed(
:slider-cols="interactiveCols"
label="Thresh Step Size"
tooltip=""
:min="1"
:min="2"
:max="128"
:step="1"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ threshStepSize: value }, false)"
Expand All @@ -49,9 +49,9 @@ const interactiveCols = computed(
:slider-cols="interactiveCols"
label="Thresh Max Size"
tooltip=""
:min="3"
:max="256"
:step="1"
:min="currentPipelineSettings.threshMinSize"
:max="255"
:step="2"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ threshMaxSize: value }, false)"
/>
<cv-slider
Expand All @@ -65,16 +65,12 @@ const interactiveCols = computed(
:step="1"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ threshConstant: value }, false)"
/>
<cv-slider
v-model="currentPipelineSettings.errorCorrectionRate"
<cv-switch
v-model="currentPipelineSettings.debugThreshold"
class="pt-2"
:slider-cols="interactiveCols"
label="Error Correction Ratio"
tooltip="Bits allowed to be corrected, expressed as a ratio of the tag families theoretical maximum."
:min="0"
:max="1.0"
:step="0.05"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ errorCorrectionRate: value }, false)"
label="Debug Threshold"
tooltip=""
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ debugThreshold: value }, false)"
/>
<cv-switch
v-model="currentPipelineSettings.useCornerRefinement"
Expand All @@ -83,54 +79,12 @@ const interactiveCols = computed(
tooltip="Further refine the initial corners with subpixel accuracy. This should be considered mandatory for 3D estimation."
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ useCornerRefinement: value }, false)"
/>
<cv-slider
v-model="currentPipelineSettings.refineNumIterations"
class="pt-2"
:slider-cols="interactiveCols"
label="Refinement Iterations"
tooltip="Maximum corner refinement iterations before stopping. Higher values can increase accuracy at the cost of performance."
:disabled="!currentPipelineSettings.useCornerRefinement"
:min="30"
:max="1000"
:step="5"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ refineNumIterations: value }, false)"
/>
<cv-slider
v-model="currentPipelineSettings.refineMinErrorPx"
class="pt-2"
:slider-cols="interactiveCols"
label="Refinement Minimum Error"
tooltip="Minimum corner refinement error in pixels before stopping. Lower values can increase accuracy at the cost of performance."
:disabled="!currentPipelineSettings.useCornerRefinement"
:min="0.01"
:max="1"
:step="0.005"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ refineMinErrorPx: value }, false)"
/>
<cv-slider
v-model="currentPipelineSettings.refineWinSize"
class="pt-2"
:slider-cols="interactiveCols"
label="Refinement Window Size"
tooltip="Ref "
:disabled="!currentPipelineSettings.useCornerRefinement"
:min="2"
:max="20"
:step="1"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ refineWinSize: value }, false)"
/>
<cv-slider
v-model="currentPipelineSettings.cornerRefinementStrategy"
<cv-switch
v-model="currentPipelineSettings.debugRefineWindow"
class="pt-2"
:slider-cols="interactiveCols"
label="Corner refinement strategy"
label="Debug Refine Window"
tooltip=""
:min="0"
:max="3"
:step="1"
@input="
(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ cornerRefinementStrategy: value }, false)
"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ debugRefineWindow: value }, false)"
/>
<cv-switch
v-model="currentPipelineSettings.useAruco3"
Expand Down
14 changes: 8 additions & 6 deletions photon-client/src/components/dashboard/tabs/TargetsTab.vue
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,9 @@ import { useStateStore } from "@/stores/StateStore";
</template>
<template
v-if="
useCameraSettingsStore().currentPipelineType === PipelineType.AprilTag &&
useCameraSettingsStore().currentPipelineSettings.solvePNPEnabled
(useCameraSettingsStore().currentPipelineType === PipelineType.AprilTag
|| useCameraSettingsStore().currentPipelineType === PipelineType.Aruco)
&& useCameraSettingsStore().currentPipelineSettings.solvePNPEnabled
"
>
<th class="text-center">Ambiguity %</th>
Expand All @@ -48,8 +49,8 @@ import { useStateStore } from "@/stores/StateStore";
<td>{{ index }}</td>
<td
v-if="
useCameraSettingsStore().currentPipelineType === PipelineType.AprilTag ||
useCameraSettingsStore().currentPipelineType === PipelineType.Aruco
useCameraSettingsStore().currentPipelineType === PipelineType.AprilTag
|| useCameraSettingsStore().currentPipelineType === PipelineType.Aruco
"
>
{{ target.fiducialId }}
Expand All @@ -67,8 +68,9 @@ import { useStateStore } from "@/stores/StateStore";
</template>
<template
v-if="
useCameraSettingsStore().currentPipelineType === PipelineType.AprilTag &&
useCameraSettingsStore().currentPipelineSettings.solvePNPEnabled
(useCameraSettingsStore().currentPipelineType === PipelineType.AprilTag
|| useCameraSettingsStore().currentPipelineType === PipelineType.Aruco)
&& useCameraSettingsStore().currentPipelineSettings.solvePNPEnabled
"
>
<td>{{ target.ambiguity?.toFixed(2) }}%</td>
Expand Down
26 changes: 11 additions & 15 deletions photon-client/src/types/PipelineTypes.ts
Original file line number Diff line number Diff line change
Expand Up @@ -245,12 +245,11 @@ export interface ArucoPipelineSettings extends PipelineSettings {
threshStepSize: number;
threshMaxSize: number;
threshConstant: number;
errorCorrectionRate: number;
useCornerRefinement: boolean;
refineNumIterations: number;
refineMinErrorPx: number;
refineWinSize: number;
cornerRefinementStrategy: number;
debugThreshold: boolean;

useCornerRefinement: boolean,
debugRefineWindow: boolean,

useAruco3: boolean;
aruco3MinMarkerSideRatio: number;
aruco3MinCanonicalImgSide: number;
Expand All @@ -266,16 +265,13 @@ export const DefaultArucoPipelineSettings: ArucoPipelineSettings = {
ledMode: false,
pipelineType: PipelineType.Aruco,

threshMinSize: 3,
threshStepSize: 10,
threshMaxSize: 23,
threshConstant: 7,
errorCorrectionRate: 0.5,
threshMinSize: 11,
threshStepSize: 40,
threshMaxSize: 91,
threshConstant: 10,
debugThreshold: false,
useCornerRefinement: true,
refineNumIterations: 30,
refineMinErrorPx: 0.1,
refineWinSize: 5,
cornerRefinementStrategy: 1,
debugRefineWindow: false,
useAruco3: false,
aruco3MinMarkerSideRatio: 0.02,
aruco3MinCanonicalImgSide: 32
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,13 @@

import java.util.List;
import org.opencv.aruco.Dictionary;
import org.opencv.core.Mat;
import org.opencv.core.MatOfPoint2f;
import org.opencv.core.Point;
import org.opencv.core.Scalar;
import org.opencv.core.Size;
import org.opencv.core.TermCriteria;
import org.opencv.imgproc.Imgproc;
import org.photonvision.vision.aruco.ArucoDetectionResult;
import org.photonvision.vision.aruco.PhotonArucoDetector;
import org.photonvision.vision.opencv.CVMat;
Expand All @@ -29,9 +36,55 @@ public class ArucoDetectionPipe
// ArucoDetector wrapper class
private final PhotonArucoDetector photonDetector = new PhotonArucoDetector();

// Ratio multiplied with image size and added to refinement window size
private static final double kRefineWindowImageRatio = 0.004;
// Ratio multiplied with max marker diagonal length and added to refinement window size
private static final double kRefineWindowMarkerRatio = 0.03;

@Override
protected List<ArucoDetectionResult> process(CVMat in) {
return List.of(photonDetector.detect(in.getMat()));
var imgMat = in.getMat();
var detections = photonDetector.detect(imgMat);
// manually do corner refinement ourselves
if (params.useCornerRefinement) {
for (var detection : detections) {
double[] xCorners = detection.getXCorners();
double[] yCorners = detection.getYCorners();
Point[] cornerPoints =
new Point[] {
new Point(xCorners[0], yCorners[0]),
new Point(xCorners[1], yCorners[1]),
new Point(xCorners[2], yCorners[2]),
new Point(xCorners[3], yCorners[3])
};
double bltr =
Math.hypot(
cornerPoints[2].x - cornerPoints[0].x, cornerPoints[2].y - cornerPoints[0].y);
double brtl =
Math.hypot(
cornerPoints[3].x - cornerPoints[1].x, cornerPoints[3].y - cornerPoints[1].y);
double minDiag = Math.min(bltr, brtl);
int halfWindowLength =
(int) Math.ceil(kRefineWindowImageRatio * Math.min(imgMat.rows(), imgMat.cols()));
halfWindowLength += (int) (minDiag * kRefineWindowMarkerRatio);
var halfWindowSize = new Size(halfWindowLength, halfWindowLength);
var ptsMat = new MatOfPoint2f(cornerPoints);
var criteria =
new TermCriteria(3, params.refinementMaxIterations, params.refinementMinErrorPx);
Imgproc.cornerSubPix(imgMat, ptsMat, halfWindowSize, new Size(-1, -1), criteria);
cornerPoints = ptsMat.toArray();
for (int i = 0; i < cornerPoints.length; i++) {
var pt = cornerPoints[i];
xCorners[i] = pt.x;
yCorners[i] = pt.y;
// If we want to debug the refinement window, draw a rectangle on the image
if (params.debugRefineWindow) {
drawCornerRefineWindow(imgMat, pt, halfWindowLength);
}
}
}
}
return List.of(detections);
}

@Override
Expand All @@ -47,13 +100,6 @@ public void setParams(ArucoDetectionPipeParams newParams) {

detectParams.set_errorCorrectionRate(newParams.errorCorrectionRate);

// detectParams.set_cornerRefinementMethod(newParams.useCornerRefinement ?
// Aruco.CORNER_REFINE_SUBPIX : Aruco.CORNER_REFINE_NONE);
detectParams.set_cornerRefinementMethod(newParams.cornerRefinementStrategy);
detectParams.set_cornerRefinementMaxIterations(newParams.refinementMaxIterations);
detectParams.set_cornerRefinementMinAccuracy(newParams.refinementMinErrorPx);
detectParams.set_cornerRefinementWinSize(newParams.refinementWindowSize);

detectParams.set_useAruco3Detection(newParams.useAruco3);
detectParams.set_minSideLengthCanonicalImg(newParams.aruco3MinCanonicalImgSide);
detectParams.set_minMarkerLengthRatioOriginalImg((float) newParams.aruco3MinMarkerSideRatio);
Expand All @@ -65,4 +111,11 @@ public void setParams(ArucoDetectionPipeParams newParams) {
public PhotonArucoDetector getPhotonDetector() {
return photonDetector;
}

private void drawCornerRefineWindow(Mat outputMat, Point corner, int windowSize) {
int thickness = (int) (Math.ceil(Math.max(outputMat.cols(), outputMat.rows()) * 0.003));
var pt1 = new Point(corner.x - windowSize, corner.y - windowSize);
var pt2 = new Point(corner.x + windowSize, corner.y + windowSize);
Imgproc.rectangle(outputMat, pt1, pt2, new Scalar(0, 0, 255), thickness);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -25,10 +25,10 @@ public class ArucoDetectionPipeParams {
/** Tag family. Default: {@link Aruco#DICT_APRILTAG_16h5}. */
public int tagFamily = Aruco.DICT_APRILTAG_16h5;

public int threshMinSize = 3;
public int threshStepSize = 10;
public int threshMaxSize = 23;
public int threshConstant = 7;
public int threshMinSize = 11;
public int threshStepSize = 40;
public int threshMaxSize = 91;
public double threshConstant = 10;

/**
* Bits allowed to be corrected, expressed as a ratio of the tag families theoretical maximum.
Expand All @@ -49,16 +49,9 @@ public class ArucoDetectionPipeParams {
* Minimum error (accuracy) for corner refinement in pixels. When a corner refinement iteration
* moves the corner by less than this value, the refinement is considered finished.
*/
public double refinementMinErrorPx = 0.1;
public double refinementMinErrorPx = 0.005;

/**
* The corner refinement window size. This is actually half the window side length.
*
* <p>Refinement window side length = (1 + refinementWindowSize * 2).
*/
public int refinementWindowSize = 5;

public int cornerRefinementStrategy = Aruco.CORNER_REFINE_SUBPIX;
public boolean debugRefineWindow = false;

/**
* If the 'Aruco3' speedup should be used. This is similar to AprilTag's 'decimate' value, but
Expand Down Expand Up @@ -90,8 +83,6 @@ public boolean equals(Object o) {
&& useCornerRefinement == that.useCornerRefinement
&& refinementMaxIterations == that.refinementMaxIterations
&& refinementMinErrorPx == that.refinementMinErrorPx
&& refinementWindowSize == that.refinementWindowSize
&& cornerRefinementStrategy == that.cornerRefinementStrategy
&& useAruco3 == that.useAruco3
&& aruco3MinMarkerSideRatio == that.aruco3MinMarkerSideRatio
&& aruco3MinCanonicalImgSide == that.aruco3MinCanonicalImgSide;
Expand All @@ -101,12 +92,14 @@ public boolean equals(Object o) {
public int hashCode() {
return Objects.hash(
tagFamily,
threshMinSize,
threshStepSize,
threshMaxSize,
threshConstant,
errorCorrectionRate,
useCornerRefinement,
refinementMaxIterations,
refinementMinErrorPx,
refinementWindowSize,
cornerRefinementStrategy,
useAruco3,
aruco3MinMarkerSideRatio,
aruco3MinCanonicalImgSide);
Expand Down
Loading

0 comments on commit 9ecac48

Please sign in to comment.