Multi-tag pnp in robot code (#787)

---------

Co-authored-by: Banks Troutman <btrout.dhrs@gmail.com>
Co-authored-by: Joseph Farkas <16584585+MrRedness@users.noreply.github.com>
This commit is contained in:
Matt
2023-02-13 17:57:01 -05:00
committed by GitHub
parent a2dfe48679
commit 5b86360b9b
33 changed files with 1785 additions and 63 deletions

View File

@@ -25,6 +25,8 @@
package org.photonvision;
import edu.wpi.first.math.geometry.Pose3d;
import java.util.List;
import org.photonvision.targeting.PhotonTrackedTarget;
/** An estimated pose based on pipeline result */
public class EstimatedRobotPose {
@@ -34,14 +36,19 @@ public class EstimatedRobotPose {
/** The estimated time the frame used to derive the robot pose was taken */
public final double timestampSeconds;
/** A list of the targets used to compute this pose */
public final List<PhotonTrackedTarget> targetsUsed;
/**
* Constructs an EstimatedRobotPose
*
* @param estimatedPose estimated pose
* @param timestampSeconds timestamp of the estimate
*/
public EstimatedRobotPose(Pose3d estimatedPose, double timestampSeconds) {
public EstimatedRobotPose(
Pose3d estimatedPose, double timestampSeconds, List<PhotonTrackedTarget> targetsUsed) {
this.estimatedPose = estimatedPose;
this.timestampSeconds = timestampSeconds;
this.targetsUsed = targetsUsed;
}
}

View File

@@ -24,9 +24,14 @@
package org.photonvision;
import edu.wpi.first.math.MatBuilder;
import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.Nat;
import edu.wpi.first.math.numbers.*;
import edu.wpi.first.networktables.BooleanPublisher;
import edu.wpi.first.networktables.BooleanSubscriber;
import edu.wpi.first.networktables.DoubleArrayPublisher;
import edu.wpi.first.networktables.DoubleArraySubscriber;
import edu.wpi.first.networktables.DoublePublisher;
import edu.wpi.first.networktables.IntegerEntry;
import edu.wpi.first.networktables.IntegerPublisher;
@@ -39,6 +44,7 @@ import edu.wpi.first.networktables.RawSubscriber;
import edu.wpi.first.networktables.StringSubscriber;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Timer;
import java.util.Optional;
import java.util.Set;
import org.photonvision.common.dataflow.structures.Packet;
import org.photonvision.common.hardware.VisionLEDMode;
@@ -64,6 +70,8 @@ public class PhotonCamera {
IntegerPublisher pipelineIndexRequest, ledModeRequest;
IntegerSubscriber pipelineIndexState, ledModeState;
IntegerSubscriber heartbeatEntry;
private DoubleArraySubscriber cameraIntrinsicsSubscriber;
private DoubleArraySubscriber cameraDistortionSubscriber;
public void close() {
rawBytesEntry.close();
@@ -84,6 +92,8 @@ public class PhotonCamera {
ledModeRequest.close();
ledModeState.close();
pipelineIndexRequest.close();
cameraIntrinsicsSubscriber.close();
cameraDistortionSubscriber.close();
}
private final String path;
@@ -133,6 +143,8 @@ public class PhotonCamera {
ledModeRequest = mainTable.getIntegerTopic("ledModeRequest").publish();
ledModeState = mainTable.getIntegerTopic("ledModeState").subscribe(-1);
versionEntry = mainTable.getStringTopic("version").subscribe("");
cameraIntrinsicsSubscriber = mainTable.getDoubleArrayTopic("cameraIntrinsics").subscribe(null);
cameraDistortionSubscriber = mainTable.getDoubleArrayTopic("cameraDistortion").subscribe(null);
m_topicNameSubscriber =
new MultiSubscriber(
@@ -305,6 +317,20 @@ public class PhotonCamera {
return (now - prevHeartbeatChangeTime) < HEARBEAT_DEBOUNCE_SEC;
}
public Optional<Matrix<N3, N3>> getCameraMatrix() {
var cameraMatrix = cameraIntrinsicsSubscriber.get();
if (cameraMatrix != null && cameraMatrix.length == 9) {
return Optional.of(new MatBuilder<>(Nat.N3(), Nat.N3()).fill(cameraMatrix));
} else return Optional.empty();
}
public Optional<Matrix<N5, N1>> getDistCoeffs() {
var distCoeffs = cameraDistortionSubscriber.get();
if (distCoeffs != null && distCoeffs.length == 5) {
return Optional.of(new MatBuilder<>(Nat.N5(), Nat.N1()).fill(distCoeffs));
} else return Optional.empty();
}
private void verifyVersion() {
if (!VERSION_CHECK_ENABLED) return;

View File

@@ -24,6 +24,7 @@
package org.photonvision;
import edu.wpi.first.apriltag.AprilTag;
import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.math.Pair;
import edu.wpi.first.math.geometry.Pose2d;
@@ -37,8 +38,10 @@ import java.util.HashSet;
import java.util.List;
import java.util.Optional;
import java.util.Set;
import org.photonvision.estimation.VisionEstimation;
import org.photonvision.targeting.PhotonPipelineResult;
import org.photonvision.targeting.PhotonTrackedTarget;
import org.photonvision.targeting.TargetCorner;
/**
* The PhotonPoseEstimator class filters or combines readings from all the AprilTags visible at a
@@ -61,11 +64,15 @@ public class PhotonPoseEstimator {
CLOSEST_TO_LAST_POSE,
/** Choose the Pose with the lowest ambiguity. */
AVERAGE_BEST_TARGETS
AVERAGE_BEST_TARGETS,
/** Use all visible tags to compute a single pose estimate.. */
MULTI_TAG_PNP
}
private AprilTagFieldLayout fieldTags;
private PoseStrategy strategy;
private PoseStrategy primaryStrategy;
private PoseStrategy multiTagFallbackStrategy = PoseStrategy.LOWEST_AMBIGUITY;
private final PhotonCamera camera;
private Transform3d robotToCamera;
@@ -93,7 +100,7 @@ public class PhotonPoseEstimator {
PhotonCamera camera,
Transform3d robotToCamera) {
this.fieldTags = fieldTags;
this.strategy = strategy;
this.primaryStrategy = strategy;
this.camera = camera;
this.robotToCamera = robotToCamera;
}
@@ -121,8 +128,8 @@ public class PhotonPoseEstimator {
*
* @return the strategy
*/
public PoseStrategy getStrategy() {
return strategy;
public PoseStrategy getPrimaryStrategy() {
return primaryStrategy;
}
/**
@@ -130,8 +137,23 @@ public class PhotonPoseEstimator {
*
* @param strategy the strategy to set
*/
public void setStrategy(PoseStrategy strategy) {
this.strategy = strategy;
public void setPrimaryStrategy(PoseStrategy strategy) {
this.primaryStrategy = strategy;
}
/**
* Set the Position Estimation Strategy used in multi-tag mode when only one tag can be seen. Must
* NOT be MULTI_TAG_PNP
*
* @param strategy the strategy to set
*/
public void setMultiTagFallbackStrategy(PoseStrategy strategy) {
if (strategy == PoseStrategy.MULTI_TAG_PNP) {
DriverStation.reportWarning(
"Fallback cannot be set to MULTI_TAG_PNP! Setting to lowest ambiguity", null);
strategy = PoseStrategy.LOWEST_AMBIGUITY;
}
this.multiTagFallbackStrategy = strategy;
}
/**
@@ -229,8 +251,13 @@ public class PhotonPoseEstimator {
return Optional.empty();
}
return update(cameraResult, this.primaryStrategy);
}
private Optional<EstimatedRobotPose> update(
PhotonPipelineResult cameraResult, PoseStrategy strat) {
Optional<EstimatedRobotPose> estimatedPose;
switch (strategy) {
switch (strat) {
case LOWEST_AMBIGUITY:
estimatedPose = lowestAmbiguityStrategy(cameraResult);
break;
@@ -245,6 +272,9 @@ public class PhotonPoseEstimator {
case AVERAGE_BEST_TARGETS:
estimatedPose = averageBestTargetsStrategy(cameraResult);
break;
case MULTI_TAG_PNP:
estimatedPose = multiTagPNPStrategy(cameraResult);
break;
default:
DriverStation.reportError(
"[PhotonPoseEstimator] Unknown Position Estimation Strategy!", false);
@@ -258,6 +288,55 @@ public class PhotonPoseEstimator {
return estimatedPose;
}
private Optional<EstimatedRobotPose> multiTagPNPStrategy(PhotonPipelineResult result) {
// Arrays we need declared up front
var visCorners = new ArrayList<TargetCorner>();
var knownVisTags = new ArrayList<AprilTag>();
var fieldToCams = new ArrayList<Pose3d>();
var fieldToCamsAlt = new ArrayList<Pose3d>();
if (result.getTargets().size() < 2) {
// Run fallback strategy instead
update(result, this.multiTagFallbackStrategy);
}
for (var target : result.getTargets()) {
visCorners.addAll(target.getDetectedCorners());
Pose3d tagPose = fieldTags.getTagPose(target.getFiducialId()).get();
// actual layout poses of visible tags -- not exposed, so have to recreate
knownVisTags.add(new AprilTag(target.getFiducialId(), tagPose));
fieldToCams.add(tagPose.transformBy(target.getBestCameraToTarget().inverse()));
fieldToCamsAlt.add(tagPose.transformBy(target.getAlternateCameraToTarget().inverse()));
}
var cameraMatrixOpt = camera.getCameraMatrix();
var distCoeffsOpt = camera.getDistCoeffs();
boolean hasCalibData = cameraMatrixOpt.isPresent() && distCoeffsOpt.isPresent();
// multi-target solvePNP
if (hasCalibData) {
var cameraMatrix = cameraMatrixOpt.get();
var distCoeffs = distCoeffsOpt.get();
var pnpResults =
VisionEstimation.estimateCamPosePNP(cameraMatrix, distCoeffs, visCorners, knownVisTags);
var best =
new Pose3d()
.plus(pnpResults.best) // field-to-camera
.plus(robotToCamera.inverse()); // field-to-robot
// var alt = new Pose3d()
// .plus(pnpResults.alt) // field-to-camera
// .plus(robotToCamera.inverse()); // field-to-robot
return Optional.of(
new EstimatedRobotPose(best, result.getTimestampSeconds(), result.getTargets()));
} else {
// TODO fallback strategy? Should we just always do solvePNP?
return Optional.empty();
}
}
/**
* Return the estimated position of the robot with the lowest position ambiguity from a List of
* pipeline results.
@@ -299,7 +378,8 @@ public class PhotonPoseEstimator {
.get()
.transformBy(lowestAmbiguityTarget.getBestCameraToTarget().inverse())
.transformBy(robotToCamera.inverse()),
result.getTimestampSeconds()));
result.getTimestampSeconds(),
result.getTargets()));
}
/**
@@ -352,7 +432,8 @@ public class PhotonPoseEstimator {
.get()
.transformBy(target.getAlternateCameraToTarget().inverse())
.transformBy(robotToCamera.inverse()),
result.getTimestampSeconds());
result.getTimestampSeconds(),
result.getTargets());
}
if (bestTransformDelta < smallestHeightDifference) {
@@ -363,7 +444,8 @@ public class PhotonPoseEstimator {
.get()
.transformBy(target.getBestCameraToTarget().inverse())
.transformBy(robotToCamera.inverse()),
result.getTimestampSeconds());
result.getTimestampSeconds(),
result.getTargets());
}
}
@@ -424,12 +506,14 @@ public class PhotonPoseEstimator {
if (altDifference < smallestPoseDelta) {
smallestPoseDelta = altDifference;
lowestDeltaPose =
new EstimatedRobotPose(altTransformPosition, result.getTimestampSeconds());
new EstimatedRobotPose(
altTransformPosition, result.getTimestampSeconds(), result.getTargets());
}
if (bestDifference < smallestPoseDelta) {
smallestPoseDelta = bestDifference;
lowestDeltaPose =
new EstimatedRobotPose(bestTransformPosition, result.getTimestampSeconds());
new EstimatedRobotPose(
bestTransformPosition, result.getTimestampSeconds(), result.getTargets());
}
}
return Optional.ofNullable(lowestDeltaPose);
@@ -471,7 +555,8 @@ public class PhotonPoseEstimator {
.get()
.transformBy(target.getBestCameraToTarget().inverse())
.transformBy(robotToCamera.inverse()),
result.getTimestampSeconds()));
result.getTimestampSeconds(),
result.getTargets()));
}
totalAmbiguity += 1.0 / target.getPoseAmbiguity();
@@ -502,7 +587,8 @@ public class PhotonPoseEstimator {
}
return Optional.of(
new EstimatedRobotPose(new Pose3d(transform, rotation), result.getTimestampSeconds()));
new EstimatedRobotPose(
new Pose3d(transform, rotation), result.getTimestampSeconds(), result.getTargets()));
}
/**

View File

@@ -24,6 +24,10 @@
package org.photonvision;
import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.numbers.N3;
import edu.wpi.first.math.numbers.N5;
import edu.wpi.first.networktables.NetworkTableInstance;
import java.util.Arrays;
import java.util.List;
@@ -52,6 +56,28 @@ public class SimPhotonCamera {
ts.updateEntries();
}
/**
* Publishes the camera intrinsics matrix. The matrix should be in the form: spotless:off
* fx 0 cx
* 0 fy cy
* 0 0 1
* @param cameraMatrix The cam matrix
* spotless:on
*/
public void setCameraIntrinsicsMat(Matrix<N3, N3> cameraMatrix) {
ts.cameraIntrinsicsPublisher.set(cameraMatrix.getData());
}
/**
* Publishes the camera distortion matrix. The matrix should be in the form [k1 k2 p1 p2 k3]. See
* more: https://docs.opencv.org/3.4/d4/d94/tutorial_camera_calibration.html
*
* @param distortionMat The distortion mat
*/
public void setCameraDistortionMat(Matrix<N5, N1> distortionMat) {
ts.cameraDistortionPublisher.set(distortionMat.getData());
}
/**
* Constructs a Simulated PhotonCamera from the name of the camera.
*

View File

@@ -0,0 +1,64 @@
/*
* MIT License
*
* Copyright (c) 2022 PhotonVision
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
package org.photonvision.estimation;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform3d;
/** Holds various helper geometries describing the relation between camera and target. */
public class CameraTargetRelation {
public final Pose3d camPose;
public final Transform3d camToTarg;
public final double camToTargDist;
public final double camToTargDistXY;
public final Rotation2d camToTargYaw;
public final Rotation2d camToTargPitch;
/** Angle from the camera's relative x-axis */
public final Rotation2d camToTargAngle;
public final Transform3d targToCam;
public final Rotation2d targToCamYaw;
public final Rotation2d targToCamPitch;
/** Angle from the target's relative x-axis */
public final Rotation2d targToCamAngle;
public CameraTargetRelation(Pose3d cameraPose, Pose3d targetPose) {
this.camPose = cameraPose;
camToTarg = new Transform3d(cameraPose, targetPose);
camToTargDist = camToTarg.getTranslation().getNorm();
camToTargDistXY =
Math.hypot(camToTarg.getTranslation().getX(), camToTarg.getTranslation().getY());
camToTargYaw = new Rotation2d(camToTarg.getX(), camToTarg.getY());
camToTargPitch = new Rotation2d(camToTargDistXY, -camToTarg.getZ());
camToTargAngle =
new Rotation2d(Math.hypot(camToTargYaw.getRadians(), camToTargPitch.getRadians()));
targToCam = new Transform3d(targetPose, cameraPose);
targToCamYaw = new Rotation2d(targToCam.getX(), targToCam.getY());
targToCamPitch = new Rotation2d(camToTargDistXY, -targToCam.getZ());
targToCamAngle =
new Rotation2d(Math.hypot(targToCamYaw.getRadians(), targToCamPitch.getRadians()));
}
}

View File

@@ -0,0 +1,518 @@
/*
* MIT License
*
* Copyright (c) 2022 PhotonVision
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
package org.photonvision.estimation;
import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.Nat;
import edu.wpi.first.math.Num;
import edu.wpi.first.math.Vector;
import edu.wpi.first.math.geometry.CoordinateSystem;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Transform3d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.math.numbers.*;
import edu.wpi.first.util.RuntimeLoader;
import java.util.ArrayList;
import java.util.Arrays;
import java.util.List;
import org.ejml.simple.SimpleMatrix;
import org.opencv.calib3d.Calib3d;
import org.opencv.core.Core;
import org.opencv.core.CvType;
import org.opencv.core.Mat;
import org.opencv.core.MatOfDouble;
import org.opencv.core.MatOfInt;
import org.opencv.core.MatOfPoint;
import org.opencv.core.MatOfPoint2f;
import org.opencv.core.MatOfPoint3f;
import org.opencv.core.Point;
import org.opencv.core.Point3;
import org.opencv.core.Rect;
import org.opencv.core.RotatedRect;
import org.opencv.imgproc.Imgproc;
import org.photonvision.targeting.TargetCorner;
public final class OpenCVHelp {
static {
try {
var loader =
new RuntimeLoader<>(
Core.NATIVE_LIBRARY_NAME, RuntimeLoader.getDefaultExtractionRoot(), Core.class);
loader.loadLibrary();
} catch (Exception e) {
throw new RuntimeException("Failed to load native libraries!", e);
}
}
public static MatOfDouble matrixToMat(SimpleMatrix matrix) {
var mat = new Mat(matrix.numRows(), matrix.numCols(), CvType.CV_64F);
mat.put(0, 0, matrix.getDDRM().getData());
var wrappedMat = new MatOfDouble();
mat.convertTo(wrappedMat, CvType.CV_64F);
mat.release();
return wrappedMat;
}
public static Matrix<Num, Num> matToMatrix(Mat mat) {
double[] data = new double[(int) mat.total() * mat.channels()];
var doubleMat = new Mat(mat.rows(), mat.cols(), CvType.CV_64F);
mat.convertTo(doubleMat, CvType.CV_64F);
doubleMat.get(0, 0, data);
return new Matrix<>(new SimpleMatrix(mat.rows(), mat.cols(), true, data));
}
/**
* Creates a new {@link MatOfPoint3f} with these 3d translations. The opencv tvec is a vector with
* three elements representing {x, y, z} in the EDN coordinate system.
*
* @param translations The translations to convert into a MatOfPoint3f
*/
public static MatOfPoint3f translationToTvec(Translation3d... translations) {
Point3[] points = new Point3[translations.length];
for (int i = 0; i < translations.length; i++) {
var trl =
CoordinateSystem.convert(translations[i], CoordinateSystem.NWU(), CoordinateSystem.EDN());
points[i] = new Point3(trl.getX(), trl.getY(), trl.getZ());
}
return new MatOfPoint3f(points);
}
/**
* Returns a new 3d translation from this {@link Mat}. The opencv tvec is a vector with three
* elements representing {x, y, z} in the EDN coordinate system.
*
* @param tvecInput The tvec to create a Translation3d from
*/
public static Translation3d tvecToTranslation(Mat tvecInput) {
float[] data = new float[3];
var wrapped = new Mat(tvecInput.rows(), tvecInput.cols(), CvType.CV_32F);
tvecInput.convertTo(wrapped, CvType.CV_32F);
wrapped.get(0, 0, data);
wrapped.release();
return CoordinateSystem.convert(
new Translation3d(data[0], data[1], data[2]),
CoordinateSystem.EDN(),
CoordinateSystem.NWU());
}
/**
* Creates a new {@link MatOfPoint3f} with this 3d rotation. The opencv rvec Mat is a vector with
* three elements representing the axis scaled by the angle in the EDN coordinate system. (angle =
* norm, and axis = rvec / norm)
*
* @param rotation The rotation to convert into a MatOfPoint3f
*/
public static MatOfPoint3f rotationToRvec(Rotation3d rotation) {
rotation = rotationNWUtoEDN(rotation);
return new MatOfPoint3f(new Point3(rotation.getQuaternion().toRotationVector().getData()));
}
/**
* Returns a 3d rotation from this {@link Mat}. The opencv rvec Mat is a vector with three
* elements representing the axis scaled by the angle in the EDN coordinate system. (angle = norm,
* and axis = rvec / norm)
*
* @param rvecInput The rvec to create a Rotation3d from
*/
public static Rotation3d rvecToRotation(Mat rvecInput) {
float[] data = new float[3];
var wrapped = new Mat(rvecInput.rows(), rvecInput.cols(), CvType.CV_32F);
rvecInput.convertTo(wrapped, CvType.CV_32F);
wrapped.get(0, 0, data);
wrapped.release();
Vector<N3> axis = new Vector<>(Nat.N3());
axis.set(0, 0, data[0]);
axis.set(1, 0, data[1]);
axis.set(2, 0, data[2]);
return rotationEDNtoNWU(new Rotation3d(axis.div(axis.norm()), axis.norm()));
}
public static TargetCorner averageCorner(List<TargetCorner> corners) {
if (corners == null || corners.size() == 0) return null;
var pointMat = targetCornersToMat(corners);
Core.reduce(pointMat, pointMat, 0, Core.REDUCE_AVG);
var avgPt = matToTargetCorners(pointMat)[0];
pointMat.release();
return avgPt;
}
public static MatOfPoint2f targetCornersToMat(List<TargetCorner> corners) {
return targetCornersToMat(corners.toArray(TargetCorner[]::new));
}
public static MatOfPoint2f targetCornersToMat(TargetCorner... corners) {
var points = new Point[corners.length];
for (int i = 0; i < corners.length; i++) {
points[i] = new Point(corners[i].x, corners[i].y);
}
return new MatOfPoint2f(points);
}
public static TargetCorner[] pointsToTargetCorners(Point... points) {
var corners = new TargetCorner[points.length];
for (int i = 0; i < points.length; i++) {
corners[i] = new TargetCorner(points[i].x, points[i].y);
}
return corners;
}
public static TargetCorner[] matToTargetCorners(MatOfPoint2f matInput) {
var corners = new TargetCorner[(int) matInput.total()];
float[] data = new float[(int) matInput.total() * matInput.channels()];
matInput.get(0, 0, data);
for (int i = 0; i < corners.length; i++) {
corners[i] = new TargetCorner(data[0 + 2 * i], data[1 + 2 * i]);
}
return corners;
}
/**
* Reorders the list, optionally indexing backwards and wrapping around to the last element after
* the first, and shifting all indices in the direction of indexing.
*
* <p>e.g.
*
* <p>({1,2,3}, false, 1) == {2,3,1}
*
* <p>({1,2,3}, true, 0) == {1,3,2}
*
* <p>({1,2,3}, true, 1) == {3,2,1}
*
* @param <T> Element type
* @param elements
* @param backwards If indexing should happen in reverse (0, size-1, size-2, ...)
* @param shiftStart How much the inital index should be shifted (instead of starting at index 0,
* start at shiftStart, negated if backwards)
* @return Reordered list
*/
public static <T> List<T> reorderCircular(List<T> elements, boolean backwards, int shiftStart) {
int size = elements.size();
int dir = backwards ? -1 : 1;
var reordered = new ArrayList<>(elements);
for (int i = 0; i < size; i++) {
int index = (i * dir + shiftStart * dir) % size;
if (index < 0) index = size + index;
reordered.set(i, elements.get(index));
}
return reordered;
}
/**
* Convert a rotation from EDN to NWU. For example, if you have a rotation X,Y,Z {1, 0, 0} in EDN,
* this would be XYZ {0, -1, 0} in NWU.
*/
private static Rotation3d rotationEDNtoNWU(Rotation3d rot) {
return CoordinateSystem.convert(
new Rotation3d(), CoordinateSystem.NWU(), CoordinateSystem.EDN())
.plus(CoordinateSystem.convert(rot, CoordinateSystem.EDN(), CoordinateSystem.NWU()));
}
/**
* Convert a rotation from EDN to NWU. For example, if you have a rotation X,Y,Z {1, 0, 0} in EDN,
* this would be XYZ {0, -1, 0} in NWU.
*/
private static Rotation3d rotationNWUtoEDN(Rotation3d rot) {
return CoordinateSystem.convert(
new Rotation3d(), CoordinateSystem.EDN(), CoordinateSystem.NWU())
.plus(CoordinateSystem.convert(rot, CoordinateSystem.NWU(), CoordinateSystem.EDN()));
}
/**
* Project object points from the 3d world into the 2d camera image. The camera
* properties(intrinsics, distortion) determine the results of this projection.
*
* @param cameraMatrix the camera intrinsics matrix in standard opencv form
* @param distCoeffs the camera distortion matrix in standard opencv form
* @param camPose The current camera pose in the 3d world
* @param objectTranslations The 3d points to be projected
* @return The 2d points in pixels which correspond to the image of the 3d points on the camera
*/
public static List<TargetCorner> projectPoints(
Matrix<N3, N3> cameraMatrix,
Matrix<N5, N1> distCoeffs,
Pose3d camPose,
List<Translation3d> objectTranslations) {
// translate to opencv classes
var objectPoints = translationToTvec(objectTranslations.toArray(new Translation3d[0]));
// opencv rvec/tvec describe a change in basis from world to camera
var basisChange = RotTrlTransform3d.makeRelativeTo(camPose);
var rvec = rotationToRvec(basisChange.getRotation());
var tvec = translationToTvec(basisChange.getTranslation());
var cameraMatrixMat = matrixToMat(cameraMatrix.getStorage());
var distCoeffsMat = matrixToMat(distCoeffs.getStorage());
var imagePoints = new MatOfPoint2f();
// project to 2d
Calib3d.projectPoints(objectPoints, rvec, tvec, cameraMatrixMat, distCoeffsMat, imagePoints);
// turn 2d point Mat into TargetCorners
var corners = matToTargetCorners(imagePoints);
// release our Mats from native memory
objectPoints.release();
rvec.release();
tvec.release();
cameraMatrixMat.release();
distCoeffsMat.release();
imagePoints.release();
return Arrays.asList(corners);
}
/**
* Undistort 2d image points using a given camera's intrinsics and distortion.
*
* <p>2d image points from projectPoints(CameraProperties, Pose3d, List) projectPoints} will
* naturally be distorted, so this operation is important if the image points need to be directly
* used (e.g. 2d yaw/pitch).
*
* @param cameraMatrix the camera intrinsics matrix in standard opencv form
* @param distCoeffs the camera distortion matrix in standard opencv form
* @param corners The distorted image points
* @return The undistorted image points
*/
public static List<TargetCorner> undistortPoints(
Matrix<N3, N3> cameraMatrix, Matrix<N5, N1> distCoeffs, List<TargetCorner> corners) {
var points_in = targetCornersToMat(corners);
var points_out = new MatOfPoint2f();
var cameraMatrixMat = matrixToMat(cameraMatrix.getStorage());
var distCoeffsMat = matrixToMat(distCoeffs.getStorage());
Calib3d.undistortImagePoints(points_in, points_out, cameraMatrixMat, distCoeffsMat);
var corners_out = matToTargetCorners(points_out);
points_in.release();
points_out.release();
cameraMatrixMat.release();
distCoeffsMat.release();
return Arrays.asList(corners_out);
}
/**
* Gets the (upright) rectangle which bounds this contour.
*
* <p>Note that rectangle size and position are stored with ints and do not have sub-pixel
* accuracy.
*
* @param corners The corners/points to be bounded
* @return Rectangle bounding the given corners
*/
public static Rect getBoundingRect(List<TargetCorner> corners) {
var corn = targetCornersToMat(corners);
var rect = Imgproc.boundingRect(corn);
corn.release();
return rect;
}
/**
* Gets the rotated rectangle with minimum area which bounds this contour.
*
* <p>Note that rectangle size and position are stored with doubles and have sub-pixel accuracy.
*
* @param corners The corners/points to be bounded
* @return Rotated rectangle bounding the given corners
*/
public static RotatedRect getMinAreaRect(List<TargetCorner> corners) {
var corn = targetCornersToMat(corners);
var rect = Imgproc.minAreaRect(corn);
corn.release();
return rect;
}
/**
* Get the area in pixels of this target's contour. It's important to note that this may be
* different from the area of the bounding rectangle around the contour.
*
* @param corners The corners defining this contour
* @return Area in pixels (units of corner x/y)
*/
public static double getContourAreaPx(List<TargetCorner> corners) {
var temp = targetCornersToMat(corners);
var corn = new MatOfPoint(temp.toArray());
temp.release();
// outputHull gives us indices (of corn) that make a convex hull contour
var outputHull = new MatOfInt();
Imgproc.convexHull(corn, outputHull);
int[] indices = outputHull.toArray();
outputHull.release();
var tempPoints = corn.toArray();
var points = tempPoints.clone();
for (int i = 0; i < indices.length; i++) {
points[i] = tempPoints[indices[i]];
}
corn.fromArray(points);
// calculate area of the (convex hull) contour
double area = Imgproc.contourArea(corn);
corn.release();
return area;
}
/**
* Finds the transformation(s) that map the camera's pose to the target pose. The camera's pose
* relative to the target is determined by the supplied 3d points of the target's model and their
* associated 2d points imaged by the camera.
*
* <p>For planar targets, there may be an alternate solution which is plausible given the 2d image
* points. This has an associated "ambiguity" which describes the ratio of reprojection error
* between the "best" and "alternate" solution.
*
* <p>This method is intended for use with individual AprilTags, and will not work unless 4 points
* are provided.
*
* @param cameraMatrix the camera intrinsics matrix in standard opencv form
* @param distCoeffs the camera distortion matrix in standard opencv form
* @param modelTrls The translations of the object corners. These should have the object pose as
* their origin. These must come in a specific, pose-relative order (in NWU):
* <ul>
* <li>Point 0: [0, -squareLength / 2, squareLength / 2]
* <li>Point 1: [0, squareLength / 2, squareLength / 2]
* <li>Point 2: [0, squareLength / 2, -squareLength / 2]
* <li>Point 3: [0, -squareLength / 2, -squareLength / 2]
* </ul>
*
* @param imageCorners The projection of these 3d object points into the 2d camera image. The
* order should match the given object point translations.
* @return The resulting transformation that maps the camera pose to the target pose and the
* ambiguity if an alternate solution is available.
*/
public static PNPResults solvePNP_SQUARE(
Matrix<N3, N3> cameraMatrix,
Matrix<N5, N1> distCoeffs,
List<Translation3d> modelTrls,
List<TargetCorner> imageCorners) {
// IPPE_SQUARE expects our corners in a specific order
modelTrls = reorderCircular(modelTrls, true, -1);
imageCorners = reorderCircular(imageCorners, true, -1);
// translate to opencv classes
var objectPoints = translationToTvec(modelTrls.toArray(new Translation3d[0]));
var imagePoints = targetCornersToMat(imageCorners);
var cameraMatrixMat = matrixToMat(cameraMatrix.getStorage());
var distCoeffsMat = matrixToMat(distCoeffs.getStorage());
var rvecs = new ArrayList<Mat>();
var tvecs = new ArrayList<Mat>();
var rvec = Mat.zeros(3, 1, CvType.CV_32F);
var tvec = Mat.zeros(3, 1, CvType.CV_32F);
var reprojectionError = new Mat();
// calc rvecs/tvecs and associated reprojection error from image points
Calib3d.solvePnPGeneric(
objectPoints,
imagePoints,
cameraMatrixMat,
distCoeffsMat,
rvecs,
tvecs,
false,
Calib3d.SOLVEPNP_IPPE_SQUARE,
rvec,
tvec,
reprojectionError);
float[] errors = new float[2];
reprojectionError.get(0, 0, errors);
// convert to wpilib coordinates
var best = new Transform3d(tvecToTranslation(tvecs.get(0)), rvecToRotation(rvecs.get(0)));
Transform3d alt = null;
if (tvecs.size() > 1) {
alt = new Transform3d(tvecToTranslation(tvecs.get(1)), rvecToRotation(rvecs.get(1)));
}
// release our Mats from native memory
objectPoints.release();
imagePoints.release();
cameraMatrixMat.release();
distCoeffsMat.release();
for (var v : rvecs) v.release();
for (var v : tvecs) v.release();
rvec.release();
tvec.release();
reprojectionError.release();
if (alt != null) return new PNPResults(best, alt, errors[0] / errors[1], errors[0], errors[1]);
else return new PNPResults(best, errors[0]);
}
/**
* Finds the transformation that maps the camera's pose to the target pose. The camera's pose
* relative to the target is determined by the supplied 3d points of the target's model and their
* associated 2d points imaged by the camera.
*
* <p>This method is intended for use with multiple targets and has no alternate solutions. There
* must be at least 3 points.
*
* @param cameraMatrix the camera intrinsics matrix in standard opencv form
* @param distCoeffs the camera distortion matrix in standard opencv form
* @param objectTrls The translations of the object corners, relative to the field.
* @param imageCorners The projection of these 3d object points into the 2d camera image. The
* order should match the given object point translations.
* @return The resulting transformation that maps the camera pose to the target pose. If the 3d
* model points are supplied relative to the origin, this transformation brings the camera to
* the origin.
*/
public static PNPResults solvePNP_SQPNP(
Matrix<N3, N3> cameraMatrix,
Matrix<N5, N1> distCoeffs,
List<Translation3d> objectTrls,
List<TargetCorner> imageCorners) {
// translate to opencv classes
var objectPoints = translationToTvec(objectTrls.toArray(new Translation3d[0]));
var imagePoints = targetCornersToMat(imageCorners);
var cameraMatrixMat = matrixToMat(cameraMatrix.getStorage());
var distCoeffsMat = matrixToMat(distCoeffs.getStorage());
var rvecs = new ArrayList<Mat>();
var tvecs = new ArrayList<Mat>();
var rvec = Mat.zeros(3, 1, CvType.CV_32F);
var tvec = Mat.zeros(3, 1, CvType.CV_32F);
var reprojectionError = new Mat();
// calc rvec/tvec from image points
Calib3d.solvePnPGeneric(
objectPoints,
imagePoints,
cameraMatrixMat,
distCoeffsMat,
rvecs,
tvecs,
false,
Calib3d.SOLVEPNP_SQPNP,
rvec,
tvec,
reprojectionError);
float[] error = new float[1];
reprojectionError.get(0, 0, error);
// convert to wpilib coordinates
var best = new Transform3d(tvecToTranslation(tvecs.get(0)), rvecToRotation(rvecs.get(0)));
// release our Mats from native memory
objectPoints.release();
imagePoints.release();
cameraMatrixMat.release();
distCoeffsMat.release();
for (var v : rvecs) v.release();
for (var v : tvecs) v.release();
rvec.release();
tvec.release();
reprojectionError.release();
return new PNPResults(best, error[0]);
}
}

View File

@@ -0,0 +1,72 @@
/*
* MIT License
*
* Copyright (c) 2022 PhotonVision
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
package org.photonvision.estimation;
import edu.wpi.first.math.geometry.Transform3d;
/**
* The best estimated transformation from solvePnP, and possibly an alternate transformation
* depending on the solvePNP method. If an alternate solution is present, the ambiguity value
* represents the ratio of reprojection error in the best solution to the alternate (best /
* alternate).
*
* <p>Note that the coordinate frame of these transforms depends on the implementing solvePnP
* method.
*/
public class PNPResults {
public final Transform3d best;
public final double bestReprojErr;
/**
* Alternate, ambiguous solution from solvepnp. If no alternate solution is found, this is equal
* to the best solution.
*/
public final Transform3d alt;
/** If no alternate solution is found, this is bestReprojErr */
public final double altReprojErr;
/** If no alternate solution is found, this is 0 */
public final double ambiguity;
public PNPResults() {
this(new Transform3d(), new Transform3d(), 0, 0, 0);
}
public PNPResults(Transform3d best, double bestReprojErr) {
this(best, best, 0, bestReprojErr, bestReprojErr);
}
public PNPResults(
Transform3d best,
Transform3d alt,
double ambiguity,
double bestReprojErr,
double altReprojErr) {
this.best = best;
this.alt = alt;
this.ambiguity = ambiguity;
this.bestReprojErr = bestReprojErr;
this.altReprojErr = altReprojErr;
}
}

View File

@@ -0,0 +1,114 @@
/*
* MIT License
*
* Copyright (c) 2022 PhotonVision
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
package org.photonvision.estimation;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Transform3d;
import edu.wpi.first.math.geometry.Translation3d;
import java.util.List;
import java.util.stream.Collectors;
/**
* Represents a transformation that first rotates a pose around the origin, and then translates it.
*/
public class RotTrlTransform3d {
private final Translation3d trl;
private final Rotation3d rot;
public RotTrlTransform3d() {
this(new Rotation3d(), new Translation3d());
}
/**
* Creates a rotation-translation transformation from a Transform3d.
*
* <p>Applying this transformation to poses will preserve their current origin-to-pose transform
* as if the origin was transformed by these components.
*
* @param trf The origin transformation
*/
public RotTrlTransform3d(Transform3d trf) {
this(trf.getRotation(), trf.getTranslation());
}
/**
* A rotation-translation transformation.
*
* <p>Applying this transformation to poses will preserve their current origin-to-pose transform
* as if the origin was transformed by these components.
*
* @param rot The rotation component
* @param trl The translation component
*/
public RotTrlTransform3d(Rotation3d rot, Translation3d trl) {
this.rot = rot;
this.trl = trl;
}
/**
* The rotation-translation transformation that makes poses in the world consider this pose as the
* new origin, or change the basis to this pose.
*
* @param pose The new origin
*/
public static RotTrlTransform3d makeRelativeTo(Pose3d pose) {
return new RotTrlTransform3d(pose.getRotation(), pose.getTranslation()).inverse();
}
/** The inverse of this transformation. Applying the inverse will "undo" this transformation. */
public RotTrlTransform3d inverse() {
var inverseRot = rot.unaryMinus();
var inverseTrl = trl.rotateBy(inverseRot).unaryMinus();
return new RotTrlTransform3d(inverseRot, inverseTrl);
}
/** This transformation as a Transform3d (as if of the origin) */
public Transform3d getTransform() {
return new Transform3d(trl, rot);
}
/** The translation component of this transformation */
public Translation3d getTranslation() {
return trl;
}
/** The rotation component of this transformation */
public Rotation3d getRotation() {
return rot;
}
public Translation3d apply(Translation3d trl) {
return apply(new Pose3d(trl, new Rotation3d())).getTranslation();
}
;
public List<Translation3d> applyTrls(List<Translation3d> trls) {
return trls.stream().map(t -> apply(t)).collect(Collectors.toList());
}
public Pose3d apply(Pose3d pose) {
return new Pose3d(pose.getTranslation().rotateBy(rot).plus(trl), pose.getRotation().plus(rot));
}
public List<Pose3d> applyPoses(List<Pose3d> poses) {
return poses.stream().map(p -> apply(p)).collect(Collectors.toList());
}
}

View File

@@ -0,0 +1,116 @@
/*
* MIT License
*
* Copyright (c) 2022 PhotonVision
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
package org.photonvision.estimation;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Transform3d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.math.util.Units;
import java.util.ArrayList;
import java.util.List;
import java.util.stream.Collectors;
/** Describes the 3d model of a target. */
public class TargetModel {
/**
* Translations of this target's vertices relative to its pose. If this target is spherical, this
* list has one translation with x == radius.
*/
public final List<Translation3d> vertices;
public final boolean isPlanar;
public final boolean isSpherical;
public static final TargetModel kTag16h5 =
new TargetModel(Units.inchesToMeters(6), Units.inchesToMeters(6));
/** Creates a rectangular, planar target model given the width and height. */
public TargetModel(double widthMeters, double heightMeters) {
this.vertices =
List.of(
// this order is relevant for AprilTag compatibility
new Translation3d(0, -widthMeters / 2.0, -heightMeters / 2.0),
new Translation3d(0, widthMeters / 2.0, -heightMeters / 2.0),
new Translation3d(0, widthMeters / 2.0, heightMeters / 2.0),
new Translation3d(0, -widthMeters / 2.0, heightMeters / 2.0));
this.isPlanar = true;
this.isSpherical = false;
}
/**
* Creates a spherical target model which has similar dimensions when viewed from any angle. This
* model will only have one vertex which has x == radius.
*/
public TargetModel(double diameterMeters) {
this.vertices = List.of(new Translation3d(diameterMeters / 2.0, 0, 0));
this.isPlanar = false;
this.isSpherical = true;
}
/**
* Creates a target model from arbitrary 3d vertices. Automatically determines if the given
* vertices are planar(x == 0). More than 2 vertices must be given.
*
* @param vertices Translations representing the vertices of this target model relative to its
* pose.
*/
public TargetModel(List<Translation3d> vertices) {
this.isSpherical = false;
if (vertices == null || vertices.size() <= 2) {
vertices = new ArrayList<>();
this.isPlanar = false;
} else {
boolean cornersPlanar = true;
for (Translation3d corner : vertices) {
if (corner.getX() != 0) cornersPlanar = false;
}
this.isPlanar = cornersPlanar;
}
this.vertices = vertices;
}
/**
* This target's vertices offset from its field pose.
*
* <p>Note: If this target is spherical, only one vertex radius meters in front of the pose is
* returned.
*/
public List<Translation3d> getFieldVertices(Pose3d targetPose) {
return vertices.stream()
.map(t -> targetPose.plus(new Transform3d(t, new Rotation3d())).getTranslation())
.collect(Collectors.toList());
}
@Override
public boolean equals(Object obj) {
if (this == obj) return true;
if (obj instanceof TargetModel) {
var o = (TargetModel) obj;
return vertices.equals(o.vertices) && isPlanar == o.isPlanar && isSpherical == o.isSpherical;
}
return false;
}
}

View File

@@ -0,0 +1,168 @@
/*
* MIT License
*
* Copyright (c) 2022 PhotonVision
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
package org.photonvision.estimation;
import edu.wpi.first.apriltag.AprilTag;
import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Transform3d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.math.numbers.*;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import java.util.ArrayList;
import java.util.List;
import org.photonvision.targeting.TargetCorner;
public class VisionEstimation {
public static final TargetModel kTagModel =
new TargetModel(Units.inchesToMeters(6), Units.inchesToMeters(6));
/**
* Performs solvePNP using 3d-2d point correspondences to estimate the field-to-camera
* transformation. If only one tag is visible, the result may have an alternate solution.
*
* <p><b>Note:</b> The returned transformation is from the field origin to the camera pose!
*
* @param cameraMatrix the camera intrinsics matrix in standard opencv form
* @param distCoeffs the camera distortion matrix in standard opencv form
* @param corners The visible tag corners in the 2d image
* @param knownTags The known tag field poses corresponding to the visible tag IDs
* @return The transformation that maps the field origin to the camera pose
*/
public static PNPResults estimateCamPosePNP(
Matrix<N3, N3> cameraMatrix,
Matrix<N5, N1> distCoeffs,
List<TargetCorner> corners,
List<AprilTag> knownTags) {
if (knownTags == null
|| corners == null
|| corners.size() != knownTags.size() * 4
|| knownTags.size() == 0) {
return new PNPResults();
}
// single-tag pnp
if (corners.size() == 4) {
var camToTag =
OpenCVHelp.solvePNP_SQUARE(
cameraMatrix, distCoeffs, kTagModel.getFieldVertices(knownTags.get(0).pose), corners);
var bestPose = knownTags.get(0).pose.transformBy(camToTag.best.inverse());
var altPose = new Pose3d();
if (camToTag.ambiguity != 0)
altPose = knownTags.get(0).pose.transformBy(camToTag.alt.inverse());
var bestTagToCam = camToTag.best.inverse();
SmartDashboard.putNumberArray(
"multiTagBest_internal",
new double[] {
bestTagToCam.getX(),
bestTagToCam.getY(),
bestTagToCam.getZ(),
bestTagToCam.getRotation().getQuaternion().getW(),
bestTagToCam.getRotation().getQuaternion().getX(),
bestTagToCam.getRotation().getQuaternion().getY(),
bestTagToCam.getRotation().getQuaternion().getZ()
});
var o = new Pose3d();
return new PNPResults(
new Transform3d(o, bestPose),
new Transform3d(o, altPose),
camToTag.ambiguity,
camToTag.bestReprojErr,
camToTag.altReprojErr);
}
// multi-tag pnp
else {
var objectTrls = new ArrayList<Translation3d>();
for (var tag : knownTags) objectTrls.addAll(kTagModel.getFieldVertices(tag.pose));
var camToOrigin = OpenCVHelp.solvePNP_SQPNP(cameraMatrix, distCoeffs, objectTrls, corners);
// var camToOrigin = OpenCVHelp.solveTagsPNPRansac(prop, objectTrls, corners);
return new PNPResults(
camToOrigin.best.inverse(),
camToOrigin.alt.inverse(),
camToOrigin.ambiguity,
camToOrigin.bestReprojErr,
camToOrigin.altReprojErr);
}
}
// /**
// * The best estimated transformation to the target, and possibly an alternate
// * transformation
// * depending on the solvePNP method. If an alternate solution is present, the
// * ambiguity value
// * represents the ratio of reprojection error in the best solution to the
// * alternate (best / alternate).
// */
// public static class PNPResults {
// public final Transform3d best;
// public final double bestReprojErr;
// /**
// * Alternate, ambiguous solution from solvepnp. This may be empty
// * if no alternate solution is found.
// */
// public final Transform3d alt;
// /** If no alternate solution is found, this is 0 */
// public final double altReprojErr;
// /** If no alternate solution is found, this is 0 */
// public final double ambiguity;
// public PNPResults() {
// this(new Transform3d(), new Transform3d(), 0, 0, 0);
// }
// public PNPResults(
// Transform3d best, Transform3d alt,
// double ambiguity, double bestReprojErr, double altReprojErr) {
// this.best = best;
// this.alt = alt;
// this.ambiguity = ambiguity;
// this.bestReprojErr = bestReprojErr;
// this.altReprojErr = altReprojErr;
// }
// }
/**
* The best estimated transformation (Rotation-translation composition) that maps a set of
* translations onto another with point correspondences, and its RMSE.
*/
public static class SVDResults {
public final RotTrlTransform3d trf;
/** If the result is invalid, this value is -1 */
public final double rmse;
public SVDResults() {
this(new RotTrlTransform3d(), -1);
}
public SVDResults(RotTrlTransform3d trf, double rmse) {
this.trf = trf;
this.rmse = rmse;
}
}
}