Skip to content

Commit

Permalink
spotless
Browse files Browse the repository at this point in the history
  • Loading branch information
amquake committed Jul 23, 2023
1 parent 4364ac2 commit 1f03b96
Show file tree
Hide file tree
Showing 5 changed files with 32 additions and 29 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -370,7 +370,7 @@ private Optional<EstimatedRobotPose> multiTagPNPStrategy(

var pnpResults =
VisionEstimation.estimateCamPosePNP(
cameraMatrixOpt.get(), distCoeffsOpt.get(), result.getTargets(), fieldTags);
cameraMatrixOpt.get(), distCoeffsOpt.get(), result.getTargets(), fieldTags);
// try fallback strategy if solvePNP fails for some reason
if (!pnpResults.isPresent)
return update(result, cameraMatrixOpt, distCoeffsOpt, this.multiTagFallbackStrategy);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,10 +36,18 @@
* method.
*/
public class PNPResults {
/** If this result is valid. A false value indicates there was an error in estimation, and this result should not be used. */
/**
* If this result is valid. A false value indicates there was an error in estimation, and this
* result should not be used.
*/
public final boolean isPresent;
/** The best-fit transform. The coordinate frame of this transform depends on the method which gave this result. */

/**
* The best-fit transform. The coordinate frame of this transform depends on the method which gave
* this result.
*/
public final Transform3d best;

/** Reprojection error of the best solution, in pixels */
public final double bestReprojErr;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,8 @@ public static List<AprilTag> getVisibleLayoutTags(
* @param distCoeffs The camera distortion matrix in standard opencv form
* @param visTags The visible tags reported by PV
* @param tagLayout The known tag layout on the field
* @return The transformation that maps the field origin to the camera pose. Ensure the {@link PNPResults} are present before utilizing them.
* @return The transformation that maps the field origin to the camera pose. Ensure the {@link
* PNPResults} are present before utilizing them.
*/
public static PNPResults estimateCamPosePNP(
Matrix<N3, N3> cameraMatrix,
Expand All @@ -91,7 +92,9 @@ public static PNPResults estimateCamPosePNP(

// single-tag pnp
if (visTags.size() == 1) {
var camToTag = OpenCVHelp.solvePNP_SQUARE(cameraMatrix, distCoeffs, TargetModel.kTag16h5.vertices, corners);
var camToTag =
OpenCVHelp.solvePNP_SQUARE(
cameraMatrix, distCoeffs, TargetModel.kTag16h5.vertices, corners);
if (!camToTag.isPresent) return new PNPResults();
var bestPose = knownTags.get(0).pose.transformBy(camToTag.best.inverse());
var altPose = new Pose3d();
Expand All @@ -100,12 +103,11 @@ public static PNPResults estimateCamPosePNP(

var o = new Pose3d();
return new PNPResults(
new Transform3d(o, bestPose),
new Transform3d(o, altPose),
camToTag.ambiguity,
camToTag.bestReprojErr,
camToTag.altReprojErr
);
new Transform3d(o, bestPose),
new Transform3d(o, altPose),
camToTag.ambiguity,
camToTag.bestReprojErr,
camToTag.altReprojErr);
}
// multi-tag pnp
else {
Expand All @@ -114,12 +116,11 @@ public static PNPResults estimateCamPosePNP(
var camToOrigin = OpenCVHelp.solvePNP_SQPNP(cameraMatrix, distCoeffs, objectTrls, corners);
if (!camToOrigin.isPresent) return new PNPResults();
return new PNPResults(
camToOrigin.best.inverse(),
camToOrigin.alt.inverse(),
camToOrigin.ambiguity,
camToOrigin.bestReprojErr,
camToOrigin.altReprojErr
);
camToOrigin.best.inverse(),
camToOrigin.alt.inverse(),
camToOrigin.ambiguity,
camToOrigin.bestReprojErr,
camToOrigin.altReprojErr);
}
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -352,10 +352,10 @@ public PhotonPipelineResult process(
if (tgt.fiducialID >= 0 && tgt.getFieldVertices().size() == 4) { // single AprilTag solvePNP
pnpSim =
OpenCVHelp.solvePNP_SQUARE(
prop.getIntrinsics(),
prop.getDistCoeffs(),
tgt.getModel().vertices,
noisyTargetCorners);
prop.getIntrinsics(),
prop.getDistCoeffs(),
tgt.getModel().vertices,
noisyTargetCorners);
if (!pnpSim.isPresent) continue;
centerRot =
prop.getPixelRot(
Expand Down
10 changes: 2 additions & 8 deletions photon-lib/src/test/java/org/photonvision/OpenCVTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -194,10 +194,7 @@ public void testSolvePNP_SQUARE() {
prop.getIntrinsics(), prop.getDistCoeffs(), cameraPose, target.getFieldVertices());
var pnpSim =
OpenCVHelp.solvePNP_SQUARE(
prop.getIntrinsics(),
prop.getDistCoeffs(),
target.getModel().vertices,
targetCorners);
prop.getIntrinsics(), prop.getDistCoeffs(), target.getModel().vertices, targetCorners);
var estRelation = new CameraTargetRelation(cameraPose, cameraPose.plus(pnpSim.best));
assertSame(actualRelation.camToTarg, estRelation.camToTarg);
}
Expand Down Expand Up @@ -225,10 +222,7 @@ public void testSolvePNP_SQPNP() {
prop.getIntrinsics(), prop.getDistCoeffs(), cameraPose, target.getFieldVertices());
var pnpSim =
OpenCVHelp.solvePNP_SQPNP(
prop.getIntrinsics(),
prop.getDistCoeffs(),
target.getModel().vertices,
targetCorners);
prop.getIntrinsics(), prop.getDistCoeffs(), target.getModel().vertices, targetCorners);
var estRelation = new CameraTargetRelation(cameraPose, cameraPose.plus(pnpSim.best));
assertSame(actualRelation.camToTarg, estRelation.camToTarg);
}
Expand Down

0 comments on commit 1f03b96

Please sign in to comment.