From 8f0cc0ab8bd9120c575e4ca8c8cbc6acd2fe990f Mon Sep 17 00:00:00 2001 From: Matt Date: Mon, 17 Jun 2024 22:38:16 -0400 Subject: [PATCH] Revert "Warn when getBestCameraToTarget returns 0, 0, 0 (#1334)" (#1351) This reverts commit 6ff7b3e1435f1751974f3152f1ab74c3dcd7051d. See #1351 for context --- .../org/photonvision/vision/target/TrackedTarget.java | 4 ---- .../native/include/photon/targeting/PhotonTrackedTarget.h | 8 +------- 2 files changed, 1 insertion(+), 11 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/vision/target/TrackedTarget.java b/photon-core/src/main/java/org/photonvision/vision/target/TrackedTarget.java index ffb3dbdfe1..9f20799763 100644 --- a/photon-core/src/main/java/org/photonvision/vision/target/TrackedTarget.java +++ b/photon-core/src/main/java/org/photonvision/vision/target/TrackedTarget.java @@ -19,7 +19,6 @@ import edu.wpi.first.apriltag.AprilTagDetection; import edu.wpi.first.apriltag.AprilTagPoseEstimate; import edu.wpi.first.math.geometry.Transform3d; -import edu.wpi.first.wpilibj.DriverStation; import java.util.ArrayList; import java.util.HashMap; import java.util.List; @@ -365,9 +364,6 @@ public boolean hasSubContours() { } public Transform3d getBestCameraToTarget3d() { - if (m_bestCameraToTarget3d.equals(new Transform3d())) { - DriverStation.reportWarning("3d mode is not enabled.", false); - } return m_bestCameraToTarget3d; } diff --git a/photon-targeting/src/main/native/include/photon/targeting/PhotonTrackedTarget.h b/photon-targeting/src/main/native/include/photon/targeting/PhotonTrackedTarget.h index e5641e7a37..bbd6721bfb 100644 --- a/photon-targeting/src/main/native/include/photon/targeting/PhotonTrackedTarget.h +++ b/photon-targeting/src/main/native/include/photon/targeting/PhotonTrackedTarget.h @@ -22,7 +22,6 @@ #include #include -#include #include #include @@ -139,12 +138,7 @@ class PhotonTrackedTarget { * reprojection error is the ambiguity, which is between 0 and 1. * @return The pose of the target relative to the robot. */ - frc::Transform3d GetBestCameraToTarget() const { - if (bestCameraToTarget == frc::Transform3d()) { - FRC_ReportError(frc::warn::Warning, "3d mode is not enabled"); - } - return bestCameraToTarget; - } + frc::Transform3d GetBestCameraToTarget() const { return bestCameraToTarget; } /** * Get the transform that maps camera space (X = forward, Y = left, Z = up) to