Skip to content

Commit

Permalink
Formatting fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
srimanachanta committed Oct 9, 2023
1 parent 724149f commit fa930b8
Show file tree
Hide file tree
Showing 4 changed files with 33 additions and 20 deletions.
12 changes: 9 additions & 3 deletions photon-client/src/components/dashboard/tabs/ArucoTab.vue
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,9 @@ const interactiveCols = computed(
:min="0"
:max="3"
:step="1"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ cornerRefinementStrategy: value }, false)"
@input="
(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ cornerRefinementStrategy: value }, false)
"
/>
<cv-switch
v-model="currentPipelineSettings.useAruco3"
Expand All @@ -146,7 +148,9 @@ const interactiveCols = computed(
:min="0"
:max="0.1"
:step="0.001"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ aruco3MinMarkerSideRatio: value }, false)"
@input="
(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ aruco3MinMarkerSideRatio: value }, false)
"
/>
<cv-slider
v-model="currentPipelineSettings.aruco3MinCanonicalImgSide"
Expand All @@ -157,7 +161,9 @@ const interactiveCols = computed(
:min="16"
:max="128"
:step="1"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ aruco3MinCanonicalImgSide: value }, false)"
@input="
(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ aruco3MinCanonicalImgSide: value }, false)
"
/>
</div>
</template>
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,6 @@
package org.photonvision.vision.pipe.impl;

import java.util.List;

import org.opencv.aruco.Aruco;
import org.opencv.aruco.Dictionary;
import org.photonvision.vision.aruco.ArucoDetectionResult;
import org.photonvision.vision.aruco.PhotonArucoDetector;
Expand All @@ -41,23 +39,24 @@ public void setParams(ArucoDetectionPipeParams newParams) {
if (this.params == null || !this.params.equals(newParams)) {
photonDetector.getDetector().set_dictionary(Dictionary.get(newParams.tagFamily));
var detectParams = photonDetector.getParams();

detectParams.set_adaptiveThreshWinSizeMin(newParams.threshMinSize);
detectParams.set_adaptiveThreshWinSizeStep(newParams.threshStepSize);
detectParams.set_adaptiveThreshWinSizeMax(newParams.threshMaxSize);
detectParams.set_adaptiveThreshConstant(newParams.threshConstant);

detectParams.set_errorCorrectionRate(newParams.errorCorrectionRate);

// detectParams.set_cornerRefinementMethod(newParams.useCornerRefinement ? Aruco.CORNER_REFINE_SUBPIX : Aruco.CORNER_REFINE_NONE);
// 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);
detectParams.set_minMarkerLengthRatioOriginalImg((float) newParams.aruco3MinMarkerSideRatio);
}

super.setParams(newParams);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,12 +32,14 @@ public class ArucoDetectionPipeParams {

/**
* Bits allowed to be corrected, expressed as a ratio of the tag families theoretical maximum.
*
*
* <p>E.g. 36h11 -> 11 * errorCorrectionRate = Max error bits
*/
public double errorCorrectionRate = 0.5;

/** If obtained corners should be iteratively refined. This should always be on for 3D estimation. */
/**
* If obtained corners should be iteratively refined. This should always be on for 3D estimation.
*/
public boolean useCornerRefinement = true;

/** Maximum corner refinement iterations. */
Expand All @@ -51,19 +53,19 @@ public class ArucoDetectionPipeParams {

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

public int cornerRefinementStrategy = Aruco.CORNER_REFINE_SUBPIX;

/**
* If the 'Aruco3' speedup should be used. This is similar to AprilTag's 'decimate' value,
* but automatically determined with the given parameters.
*
* If the 'Aruco3' speedup should be used. This is similar to AprilTag's 'decimate' value, but
* automatically determined with the given parameters.
*
* <p>T_i = aruco3MinMarkerSideRatio, and T_c = aruco3MinCanonicalImgSide
*
*
* <p>Scale factor = T_c / (T_c + T_i * max(img_width, img_height))
*/
public boolean useAruco3 = false;
Expand Down Expand Up @@ -98,8 +100,15 @@ public boolean equals(Object o) {
@Override
public int hashCode() {
return Objects.hash(
tagFamily, errorCorrectionRate, useCornerRefinement, refinementMaxIterations,
refinementMinErrorPx, refinementWindowSize, cornerRefinementStrategy, useAruco3,
aruco3MinMarkerSideRatio, aruco3MinCanonicalImgSide);
tagFamily,
errorCorrectionRate,
useCornerRefinement,
refinementMaxIterations,
refinementMinErrorPx,
refinementWindowSize,
cornerRefinementStrategy,
useAruco3,
aruco3MinMarkerSideRatio,
aruco3MinCanonicalImgSide);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
package org.photonvision.vision.pipeline;

import com.fasterxml.jackson.annotation.JsonTypeName;

import org.opencv.aruco.Aruco;
import org.photonvision.vision.target.TargetModel;

Expand Down

0 comments on commit fa930b8

Please sign in to comment.