Skip to content

Commit

Permalink
Change default AprilTag family to 36h11 (#1333)
Browse files Browse the repository at this point in the history
Change default AprilTag family to 36h11

Resolves #1226
  • Loading branch information
spacey-sooty authored May 31, 2024
1 parent f792b46 commit e34b114
Show file tree
Hide file tree
Showing 5 changed files with 10 additions and 10 deletions.
8 changes: 4 additions & 4 deletions photon-client/src/types/PipelineTypes.ts
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand All @@ -233,7 +233,7 @@ export const DefaultAprilTagPipelineSettings: AprilTagPipelineSettings = {
refineEdges: true,
debug: false,
threads: 4,
tagFamily: AprilTagFamily.Family16h5,
tagFamily: AprilTagFamily.Family36h11,
doMultiTarget: false,
doSingleTargetAlways: false
};
Expand Down Expand Up @@ -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,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -169,7 +169,7 @@ public void setFieldTags(AprilTagFieldLayout fieldTags) {
/**
* Get the TargetModel representing the tags being detected. This is used for on-rio multitag.
*
* <p>By default, this is {@link TargetModel#kAprilTag16h5}.
* <p>By default, this is {@link TargetModel#kAprilTag36h11}.
*/
public TargetModel getTagModel() {
return tagModel;
Expand Down

0 comments on commit e34b114

Please sign in to comment.