Skip to content

Commit

Permalink
shootTags added
Browse files Browse the repository at this point in the history
  • Loading branch information
Wi11iamYuan committed Mar 27, 2024
1 parent ee4596e commit dc12580
Showing 1 changed file with 32 additions and 4 deletions.
36 changes: 32 additions & 4 deletions src/main/java/common/hardware/camera/Camera.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
import java.util.function.BiConsumer;
import java.util.function.Supplier;
import java.util.ArrayList;
import java.util.HashMap;

import org.littletonrobotics.junction.Logger;
import org.photonvision.EstimatedRobotPose;
Expand All @@ -31,6 +32,12 @@
*/
public class Camera {

public static boolean areShootTagsSeen = false;

private static ArrayList<Integer> shootTags = new ArrayList<Integer>();

private static HashMap<Camera, Boolean> shootTagsSeen = new HashMap<Camera, Boolean>();

public static int updateCounter = 0;

public static double validDist = 0.5;
Expand All @@ -49,7 +56,7 @@ public class Camera {
private static Supplier<Pose2d> robotPose;
private static double ambiguityThreshold = 0.2;

private static ArrayList<Double> ignoredTags = new ArrayList<Double>();
private static ArrayList<Integer> ignoredTags = new ArrayList<Integer>();

public static final LinkedList<Camera> cameras = new LinkedList<Camera>();

Expand All @@ -71,6 +78,7 @@ public Camera(String name, double xOffset, double yOffset, double yawOffset, dou
}

cameras.add(this);
shootTagsSeen.put(this, false);
}

public static void configCameras(AprilTagFields aprilTagLayout, PoseStrategy calc_strategy, BiConsumer<Pose2d, Double> odometry, Supplier<Pose2d> robotPose){
Expand All @@ -80,12 +88,28 @@ public static void configCameras(AprilTagFields aprilTagLayout, PoseStrategy cal
Camera.robotPose = robotPose;
}

public static void addIgnoredTags(double ...ignoredTags) {
for(final double tag : ignoredTags) {
public static void addIgnoredTags(int ...ignoredTags) {
for(final int tag : ignoredTags) {
Camera.ignoredTags.add(tag);
}
}

public static void addShootTags(int ...shootTags) {
for(final int tag : shootTags) {
Camera.shootTags.add(tag);
}
}

public static void checkShootTagsAll(){
for (final Camera camera : cameras) {
if(shootTagsSeen.get(camera)) {
areShootTagsSeen = true;
return;
}
}
areShootTagsSeen = false;
}

public static void updateAll(){
for (final Camera camera : cameras) {
camera.update();
Expand Down Expand Up @@ -120,9 +144,13 @@ private Optional<EstimatedRobotPose> getEstimatedPose(PhotonPipelineResult resul
for (PhotonTrackedTarget target : result.targets) {
double targetPoseAmbiguity = target.getPoseAmbiguity();
double dist = target.getBestCameraToTarget().getTranslation().toTranslation2d().getNorm();
if (dist > distanceThreshold || targetPoseAmbiguity > ambiguityThreshold || ignoredTags.contains(Double.valueOf(target.getFiducialId()))) continue;
if (dist > distanceThreshold || targetPoseAmbiguity > ambiguityThreshold || ignoredTags.contains(Integer.valueOf(target.getFiducialId()))) continue;
// Make sure the target is a Fiducial target.

if(shootTags.contains(Integer.valueOf(target.getFiducialId()))) {
shootTagsSeen.put(this, true);
}

if (targetPoseAmbiguity != -1 && targetPoseAmbiguity < lowestAmbiguityScore) {
lowestAmbiguityScore = targetPoseAmbiguity;
lowestAmbiguityTarget = target;
Expand Down

0 comments on commit dc12580

Please sign in to comment.