From f2cbc907d88fc3c7c261621e4fb0355f717fa106 Mon Sep 17 00:00:00 2001 From: amquake Date: Tue, 24 Oct 2023 20:07:51 -0700 Subject: [PATCH] tag layout as field --- .../java/org/photonvision/simulation/PhotonCameraSim.java | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/photon-lib/src/main/java/org/photonvision/simulation/PhotonCameraSim.java b/photon-lib/src/main/java/org/photonvision/simulation/PhotonCameraSim.java index c96c2d12b0..8e427bcbdd 100644 --- a/photon-lib/src/main/java/org/photonvision/simulation/PhotonCameraSim.java +++ b/photon-lib/src/main/java/org/photonvision/simulation/PhotonCameraSim.java @@ -24,6 +24,7 @@ package org.photonvision.simulation; +import edu.wpi.first.apriltag.AprilTagFieldLayout; import edu.wpi.first.apriltag.AprilTagFields; import edu.wpi.first.cameraserver.CameraServer; import edu.wpi.first.cscore.CvSource; @@ -81,6 +82,8 @@ public class PhotonCameraSim implements AutoCloseable { private double minTargetAreaPercent; private PhotonTargetSortMode sortMode = PhotonTargetSortMode.Largest; + private AprilTagFieldLayout tagLayout = AprilTagFields.kDefaultField.loadAprilTagLayoutField(); + // video stream simulation private final CvSource videoSimRaw; private final Mat videoSimFrameRaw = new Mat(); @@ -532,7 +535,6 @@ public PhotonPipelineResult process( var multitagResults = new MultiTargetPNPResults(); // TODO: Implement ATFL subscribing in backend // var tagLayout = cam.getAprilTagFieldLayout(); - var tagLayout = AprilTagFields.kDefaultField.loadAprilTagLayoutField(); var visibleLayoutTags = VisionEstimation.getVisibleLayoutTags(detectableTgts, tagLayout); if (visibleLayoutTags.size() > 1) { List usedIDs =