From f44aa7582da3a4565b3a5af833dca93dd77b2a4f Mon Sep 17 00:00:00 2001 From: Matthew Morley Date: Sun, 15 Oct 2023 14:00:39 -0400 Subject: [PATCH] Run lint and fix imports --- .../common/configuration/LegacyConfigProvider.java | 3 ++- .../common/configuration/SqlConfigProvider.java | 3 ++- .../photonvision/vision/pipeline/AprilTagPipeline.java | 8 +++++--- .../org/photonvision/vision/target/TrackedTarget.java | 1 + 4 files changed, 10 insertions(+), 5 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/LegacyConfigProvider.java b/photon-core/src/main/java/org/photonvision/common/configuration/LegacyConfigProvider.java index 4b7e5857cb..74d5d472fe 100644 --- a/photon-core/src/main/java/org/photonvision/common/configuration/LegacyConfigProvider.java +++ b/photon-core/src/main/java/org/photonvision/common/configuration/LegacyConfigProvider.java @@ -22,6 +22,7 @@ import edu.wpi.first.apriltag.AprilTagFields; import java.io.File; import java.io.IOException; +import java.io.UncheckedIOException; import java.nio.file.Files; import java.nio.file.Path; import java.text.DateFormat; @@ -198,7 +199,7 @@ public void load() { logger.info("Loading default apriltags for 2023 field..."); try { atfl = AprilTagFields.kDefaultField.loadAprilTagLayoutField(); - } catch (IOException e) { + } catch (UncheckedIOException e) { logger.error("Error loading WPILib field", e); atfl = null; } diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/SqlConfigProvider.java b/photon-core/src/main/java/org/photonvision/common/configuration/SqlConfigProvider.java index d0960f3a14..8a0c755ad8 100644 --- a/photon-core/src/main/java/org/photonvision/common/configuration/SqlConfigProvider.java +++ b/photon-core/src/main/java/org/photonvision/common/configuration/SqlConfigProvider.java @@ -21,6 +21,7 @@ import edu.wpi.first.apriltag.AprilTagFields; import java.io.File; import java.io.IOException; +import java.io.UncheckedIOException; import java.nio.file.Files; import java.nio.file.Path; import java.sql.*; @@ -241,7 +242,7 @@ public void load() { logger.error("Could not deserialize apriltag layout! Loading defaults"); try { atfl = AprilTagFields.kDefaultField.loadAprilTagLayoutField(); - } catch (IOException e2) { + } catch (UncheckedIOException e2) { logger.error("Error loading WPILib field", e); atfl = null; } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java index e324437c07..d1837ff770 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java @@ -38,8 +38,9 @@ import org.photonvision.vision.pipe.impl.AprilTagDetectionPipeParams; import org.photonvision.vision.pipe.impl.AprilTagPoseEstimatorPipe; import org.photonvision.vision.pipe.impl.AprilTagPoseEstimatorPipe.AprilTagPoseEstimatorPipeParams; -import org.photonvision.vision.pipe.impl.MultiTargetPNPPipe.MultiTargetPNPPipeParams; import org.photonvision.vision.pipe.impl.CalculateFPSPipe; +import org.photonvision.vision.pipe.impl.MultiTargetPNPPipe; +import org.photonvision.vision.pipe.impl.MultiTargetPNPPipe.MultiTargetPNPPipeParams; import org.photonvision.vision.pipeline.result.CVPipelineResult; import org.photonvision.vision.target.TrackedTarget; import org.photonvision.vision.target.TrackedTarget.TargetCalculationParameters; @@ -220,8 +221,9 @@ protected CVPipelineResult process(Frame frame, AprilTagPipelineSettings setting false, null, null, null, null, frameStaticProperties)); var correctedBestPose = - MathUtils.convertOpenCVtoPhotonPose(target.getBestCameraToTarget3d()); - var correctedAltPose = MathUtils.convertOpenCVtoPhotonPose(target.getAltCameraToTarget3d()); + MathUtils.convertOpenCVtoPhotonTransform(target.getBestCameraToTarget3d()); + var correctedAltPose = + MathUtils.convertOpenCVtoPhotonTransform(target.getAltCameraToTarget3d()); target.setBestCameraToTarget3d( new Transform3d(correctedBestPose.getTranslation(), correctedBestPose.getRotation())); 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 1b0dcb9a39..9be1e9162c 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 @@ -31,6 +31,7 @@ import org.opencv.core.MatOfPoint2f; import org.opencv.core.Point; import org.opencv.core.RotatedRect; +import org.photonvision.common.util.SerializationUtils; import org.photonvision.common.util.math.MathUtils; import org.photonvision.targeting.PhotonTrackedTarget; import org.photonvision.targeting.TargetCorner;