Skip to content

Commit

Permalink
Add 36h11 tag model for 2024 (#951)
Browse files Browse the repository at this point in the history
* Add 36h11 model

* Formatting fixes

* Match frontend TargetModel enum with backend

* fix target model merge

* Update TargetModel.java

---------

Co-authored-by: Sriman Achanta <[email protected]>
  • Loading branch information
mcm001 and srimanachanta authored Oct 25, 2023
1 parent adc3033 commit cb401e1
Show file tree
Hide file tree
Showing 5 changed files with 39 additions and 33 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ const interactiveCols = computed(
<pv-select
v-model="currentPipelineSettings.tagFamily"
label="Target family"
:items="['AprilTag Family 36h11', 'AprilTag Family 25h9', 'AprilTag Family 16h5']"
:items="['AprilTag 36h11 (6.5in)', 'AprilTag 25h9 (6in)', 'AprilTag 16h5 (6in)']"
:select-cols="interactiveCols"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ tagFamily: value }, false)"
/>
Expand Down
9 changes: 5 additions & 4 deletions photon-client/src/components/dashboard/tabs/PnPTab.vue
Original file line number Diff line number Diff line change
Expand Up @@ -21,15 +21,16 @@ const interactiveCols = computed(
v-model="useCameraSettingsStore().currentPipelineSettings.targetModel"
label="Target Model"
:items="[
{ name: '2020 High Goal Outer', value: TargetModel.InfiniteRechargeHighGoalOuter },
{ name: '2020 High Goal Inner', value: TargetModel.InfiniteRechargeHighGoalInner },
{ name: '2016 High Goal', value: TargetModel.StrongholdHighGoal },
{ name: '2019 Dual Target', value: TargetModel.DeepSpaceDualTarget },
{ name: '2020 High Goal Outer', value: TargetModel.InfiniteRechargeHighGoalOuter },
{ name: '2020 Power Cell (7in)', value: TargetModel.CircularPowerCell7in },
{ name: '2022 Cargo Ball (9.5in)', value: TargetModel.RapidReactCircularCargoBall },
{ name: '2016 High Goal', value: TargetModel.StrongholdHighGoal },
{ name: '200mm AprilTag', value: TargetModel.Apriltag_200mm },
{ name: '6in (16h5) Aruco', value: TargetModel.Aruco6in_16h5 },
{ name: '6in (16h5) AprilTag', value: TargetModel.Apriltag6in_16h5 }
{ name: '6in (16h5) AprilTag', value: TargetModel.Apriltag6in_16h5 },
{ name: '6.5in (36h11) Aruco', value: TargetModel.Aruco6p5in_36h11 },
{ name: '6.5in (36h11) AprilTag', value: TargetModel.Apriltag6p5in_36h11 }
]"
:select-cols="interactiveCols"
@input="(value) => useCameraSettingsStore().changeCurrentPipelineSetting({ targetModel: value }, false)"
Expand Down
15 changes: 8 additions & 7 deletions photon-client/src/types/PipelineTypes.ts
Original file line number Diff line number Diff line change
Expand Up @@ -21,15 +21,16 @@ export enum RobotOffsetPointMode {
}

export enum TargetModel {
InfiniteRechargeHighGoalOuter = 0,
InfiniteRechargeHighGoalInner = 1,
DeepSpaceDualTarget = 2,
StrongholdHighGoal = 0,
DeepSpaceDualTarget = 1,
InfiniteRechargeHighGoalOuter = 2,
CircularPowerCell7in = 3,
RapidReactCircularCargoBall = 4,
StrongholdHighGoal = 5,
Apriltag_200mm = 6,
Aruco6in_16h5 = 7,
Apriltag6in_16h5 = 8
Apriltag_200mm = 5,
Aruco6in_16h5 = 6,
Apriltag6in_16h5 = 7,
Aruco6p5in_36h11 = 8,
Apriltag6p5in_36h11 = 9
}

export interface PipelineSettings {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
import org.photonvision.common.configuration.ConfigManager;
import org.photonvision.common.util.math.MathUtils;
import org.photonvision.targeting.MultiTargetPNPResults;
import org.photonvision.vision.apriltag.AprilTagFamily;
import org.photonvision.vision.frame.Frame;
import org.photonvision.vision.frame.FrameThresholdType;
import org.photonvision.vision.pipe.CVPipe.CVPipeResult;
Expand Down Expand Up @@ -69,27 +70,15 @@ protected void setPipeParamsImpl() {
// Sanitize thread count - not supported to have fewer than 1 threads
settings.threads = Math.max(1, settings.threads);

// if (cameraQuirks.hasQuirk(CameraQuirk.PiCam) && LibCameraJNI.isSupported()) {
// // TODO: Picam grayscale
// LibCameraJNI.setRotation(settings.inputImageRotationMode.value);
// // LibCameraJNI.setShouldCopyColor(true); // need the color image to grayscale
// }

// TODO (HACK): tag width is Fun because it really belongs in the "target model"
// We need the tag width for the JNI to figure out target pose, but we need a
// target model for the draw 3d targets pipeline to work...

// for now, hard code tag width based on enum value
double tagWidth = Units.inchesToMeters(3 * 2); // for 6in 16h5 tag.

// AprilTagDetectorParams aprilTagDetectionParams =
// new AprilTagDetectorParams(
// settings.tagFamily,
// settings.decimate,
// settings.blur,
// settings.threads,
// settings.debug,
// settings.refineEdges);
double tagWidth;
if (settings.tagFamily == AprilTagFamily.kTag36h11) {
// 2024 tag, guess 6.5in
tagWidth = Units.inchesToMeters(6.5);
} else {
// 2023/other: best guess is 6in
tagWidth = Units.inchesToMeters(6);
}

var config = new AprilTagDetector.Config();
config.numThreads = settings.threads;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,22 @@ public enum TargetModel implements Releasable {
new Point3(-Units.inchesToMeters(3), Units.inchesToMeters(3), 0),
new Point3(-Units.inchesToMeters(3), -Units.inchesToMeters(3), 0),
new Point3(Units.inchesToMeters(3), -Units.inchesToMeters(3), 0)),
Units.inchesToMeters(3 * 2));
Units.inchesToMeters(3 * 2)),
// 2024 FRC tag. 6.5in inner tag, 8.125 overall
kAruco6p5in_36h11(
List.of(
new Point3(Units.inchesToMeters(6.5 / 2.0), Units.inchesToMeters(6.5 / 2.0), 0),
new Point3(Units.inchesToMeters(6.5 / 2.0), -Units.inchesToMeters(6.5 / 2.0), 0),
new Point3(-Units.inchesToMeters(6.5 / 2.0), -Units.inchesToMeters(6.5 / 2.0), 0),
new Point3(Units.inchesToMeters(6.5 / 2.0), -Units.inchesToMeters(6.5 / 2.0), 0)),
Units.inchesToMeters(6.5)),
k6p5in_36h11(
List.of(
new Point3(-Units.inchesToMeters(6.5 / 2.0), Units.inchesToMeters(6.5 / 2.0), 0),
new Point3(Units.inchesToMeters(6.5 / 2.0), Units.inchesToMeters(6.5 / 2.0), 0),
new Point3(Units.inchesToMeters(6.5 / 2.0), -Units.inchesToMeters(6.5 / 2.0), 0),
new Point3(-Units.inchesToMeters(6.5 / 2.0), -Units.inchesToMeters(6.5 / 2.0), 0)),
Units.inchesToMeters(6.5));

@JsonIgnore private MatOfPoint3f realWorldTargetCoordinates;
@JsonIgnore private final MatOfPoint3f visualizationBoxBottom = new MatOfPoint3f();
Expand Down

0 comments on commit cb401e1

Please sign in to comment.