From e34b114669b30e529a91381865853514fcc88eb1 Mon Sep 17 00:00:00 2001 From: Jade Date: Fri, 31 May 2024 08:30:40 +0800 Subject: [PATCH] Change default AprilTag family to 36h11 (#1333) Change default AprilTag family to 36h11 Resolves https://github.com/PhotonVision/photonvision/issues/1226 --- photon-client/src/types/PipelineTypes.ts | 8 ++++---- .../vision/pipe/impl/ArucoDetectionPipeParams.java | 4 ++-- .../vision/pipeline/AprilTagPipelineSettings.java | 2 +- .../vision/pipeline/ArucoPipelineSettings.java | 2 +- .../main/java/org/photonvision/PhotonPoseEstimator.java | 4 ++-- 5 files changed, 10 insertions(+), 10 deletions(-) diff --git a/photon-client/src/types/PipelineTypes.ts b/photon-client/src/types/PipelineTypes.ts index 740572a8db..6315a23e72 100644 --- a/photon-client/src/types/PipelineTypes.ts +++ b/photon-client/src/types/PipelineTypes.ts @@ -219,7 +219,7 @@ export type ConfigurableAprilTagPipelineSettings = Partial< export const DefaultAprilTagPipelineSettings: AprilTagPipelineSettings = { ...DefaultPipelineSettings, cameraGain: 75, - targetModel: TargetModel.AprilTag6in_16h5, + targetModel: TargetModel.AprilTag6p5in_36h11, ledMode: false, outputShowMultipleTargets: true, cameraExposure: 20, @@ -233,7 +233,7 @@ export const DefaultAprilTagPipelineSettings: AprilTagPipelineSettings = { refineEdges: true, debug: false, threads: 4, - tagFamily: AprilTagFamily.Family16h5, + tagFamily: AprilTagFamily.Family36h11, doMultiTarget: false, doSingleTargetAlways: false }; @@ -263,13 +263,13 @@ export const DefaultArucoPipelineSettings: ArucoPipelineSettings = { ...DefaultPipelineSettings, cameraGain: 75, outputShowMultipleTargets: true, - targetModel: TargetModel.AprilTag6in_16h5, + targetModel: TargetModel.AprilTag6p5in_36h11, cameraExposure: -1, cameraAutoExposure: true, ledMode: false, pipelineType: PipelineType.Aruco, - tagFamily: AprilTagFamily.Family16h5, + tagFamily: AprilTagFamily.Family36h11, threshWinSizes: { first: 11, second: 91 }, threshStepSize: 40, threshConstant: 10, diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ArucoDetectionPipeParams.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ArucoDetectionPipeParams.java index b28ae9a89f..a89d2c03c3 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ArucoDetectionPipeParams.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ArucoDetectionPipeParams.java @@ -22,8 +22,8 @@ /** Detector parameters. See https://docs.opencv.org/4.x/d5/dae/tutorial_aruco_detection.html. */ public class ArucoDetectionPipeParams { - /** Tag family. Default: {@link Objdetect#DICT_APRILTAG_16h5}. */ - public int tagFamily = Objdetect.DICT_APRILTAG_16h5; + /** Tag family. Default: {@link Objdetect#DICT_APRILTAG_36h11}. */ + public int tagFamily = Objdetect.DICT_APRILTAG_36h11; public int threshMinSize = 11; public int threshStepSize = 40; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipelineSettings.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipelineSettings.java index 31da770127..8583cd4d5f 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipelineSettings.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipelineSettings.java @@ -41,7 +41,7 @@ public AprilTagPipelineSettings() { super(); pipelineType = PipelineType.AprilTag; outputShowMultipleTargets = true; - targetModel = TargetModel.kAprilTag6in_16h5; + targetModel = TargetModel.kAprilTag6p5in_36h11; cameraExposure = 20; cameraAutoExposure = false; ledMode = false; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipelineSettings.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipelineSettings.java index 2690034db4..972951c2a6 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipelineSettings.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipelineSettings.java @@ -46,7 +46,7 @@ public ArucoPipelineSettings() { super(); pipelineType = PipelineType.Aruco; outputShowMultipleTargets = true; - targetModel = TargetModel.kAprilTag6in_16h5; + targetModel = TargetModel.kAprilTag6p5in_36h11; cameraExposure = -1; cameraAutoExposure = true; ledMode = false; diff --git a/photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java b/photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java index 2460288d03..af93968c41 100644 --- a/photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java +++ b/photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java @@ -87,7 +87,7 @@ public enum PoseStrategy { } private AprilTagFieldLayout fieldTags; - private TargetModel tagModel = TargetModel.kAprilTag16h5; + private TargetModel tagModel = TargetModel.kAprilTag36h11; private PoseStrategy primaryStrategy; private PoseStrategy multiTagFallbackStrategy = PoseStrategy.LOWEST_AMBIGUITY; private final PhotonCamera camera; @@ -169,7 +169,7 @@ public void setFieldTags(AprilTagFieldLayout fieldTags) { /** * Get the TargetModel representing the tags being detected. This is used for on-rio multitag. * - *

By default, this is {@link TargetModel#kAprilTag16h5}. + *

By default, this is {@link TargetModel#kAprilTag36h11}. */ public TargetModel getTagModel() { return tagModel;