Skip to content

Commit

Permalink
Run lint and fix imports
Browse files Browse the repository at this point in the history
  • Loading branch information
mcm001 committed Oct 15, 2023
1 parent cd351f6 commit f44aa75
Show file tree
Hide file tree
Showing 4 changed files with 10 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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.*;
Expand Down Expand Up @@ -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;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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()));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit f44aa75

Please sign in to comment.