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.pipe.impl; 019 020import java.util.Objects; 021import org.opencv.objdetect.Objdetect; 022 023/** Detector parameters. See https://docs.opencv.org/4.x/d5/dae/tutorial_aruco_detection.html. */ 024public class ArucoDetectionPipeParams { 025 /** Tag family. Default: {@link Objdetect#DICT_APRILTAG_36h11}. */ 026 public int tagFamily = Objdetect.DICT_APRILTAG_36h11; 027 028 public int threshMinSize = 11; 029 public int threshStepSize = 40; 030 public int threshMaxSize = 91; 031 public double threshConstant = 10; 032 033 /** 034 * Bits allowed to be corrected, expressed as a ratio of the tag families theoretical maximum. 035 * 036 * <p>E.g. 36h11 = 11 * errorCorrectionRate = Max error bits 037 */ 038 public double errorCorrectionRate = 0; 039 040 /** 041 * If obtained corners should be iteratively refined. This should always be on for 3D estimation. 042 */ 043 public boolean useCornerRefinement = true; 044 045 /** Maximum corner refinement iterations. */ 046 public int refinementMaxIterations = 30; 047 048 /** 049 * Minimum error (accuracy) for corner refinement in pixels. When a corner refinement iteration 050 * moves the corner by less than this value, the refinement is considered finished. 051 */ 052 public double refinementMinErrorPx = 0.005; 053 054 public boolean debugRefineWindow = false; 055 056 /** 057 * If the 'Aruco3' speedup should be used. This is similar to AprilTag's 'decimate' value, but 058 * automatically determined with the given parameters. 059 * 060 * <p>T_i = aruco3MinMarkerSideRatio, and T_c = aruco3MinCanonicalImgSide 061 * 062 * <p>Scale factor = T_c / (T_c + T_i * max(img_width, img_height)) 063 */ 064 public boolean useAruco3 = false; 065 066 /** Minimum side length of markers expressed as a ratio of the largest image dimension. */ 067 public double aruco3MinMarkerSideRatio = 0.02; 068 069 /** Minimum side length of the canonical image (marker after undoing perspective distortion). */ 070 public int aruco3MinCanonicalImgSide = 32; 071 072 @Override 073 public boolean equals(Object o) { 074 if (this == o) return true; 075 if (o == null || getClass() != o.getClass()) return false; 076 ArucoDetectionPipeParams that = (ArucoDetectionPipeParams) o; 077 return tagFamily == that.tagFamily 078 && threshMinSize == that.threshMinSize 079 && threshStepSize == that.threshStepSize 080 && threshMaxSize == that.threshMaxSize 081 && threshConstant == that.threshConstant 082 && errorCorrectionRate == that.errorCorrectionRate 083 && useCornerRefinement == that.useCornerRefinement 084 && refinementMaxIterations == that.refinementMaxIterations 085 && refinementMinErrorPx == that.refinementMinErrorPx 086 && useAruco3 == that.useAruco3 087 && aruco3MinMarkerSideRatio == that.aruco3MinMarkerSideRatio 088 && aruco3MinCanonicalImgSide == that.aruco3MinCanonicalImgSide; 089 } 090 091 @Override 092 public int hashCode() { 093 return Objects.hash( 094 tagFamily, 095 threshMinSize, 096 threshStepSize, 097 threshMaxSize, 098 threshConstant, 099 errorCorrectionRate, 100 useCornerRefinement, 101 refinementMaxIterations, 102 refinementMinErrorPx, 103 useAruco3, 104 aruco3MinMarkerSideRatio, 105 aruco3MinCanonicalImgSide); 106 } 107}