mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-21 01:01:41 +00:00
Fix javadoc warnings (#2266)
Persuant to #1093, I added as many docstrings as I could, at least for things I knew about. Some of the classes I just suppressed the Javadoc warnings in because they aren't particularly useful to document. This gets us down to less than 100 Javadoc warnings in total. Docs for core classes on the C++ side were also added for parity.
This commit is contained in:
@@ -24,6 +24,7 @@ import java.util.Optional;
|
||||
import org.photonvision.targeting.serde.PhotonStructSerializable;
|
||||
|
||||
/** A packet that holds byte-packed data to be sent over NetworkTables. */
|
||||
@SuppressWarnings("doclint")
|
||||
public class Packet {
|
||||
// Data stored in the packet.
|
||||
byte[] packetData;
|
||||
|
||||
@@ -19,6 +19,7 @@ package org.photonvision.common.dataflow.structures;
|
||||
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
|
||||
@SuppressWarnings("doclint")
|
||||
public interface PacketSerde<T> {
|
||||
int getMaxByteSize();
|
||||
|
||||
|
||||
@@ -24,7 +24,7 @@ import java.nio.file.Files;
|
||||
import java.nio.file.Paths;
|
||||
import java.util.function.Supplier;
|
||||
|
||||
@SuppressWarnings("unused")
|
||||
@SuppressWarnings({"unused", "doclint"})
|
||||
public enum Platform {
|
||||
// WPILib Supported (JNI)
|
||||
WINDOWS_64("Windows x64", Platform::getUnknownModel, false, OSType.WINDOWS, true),
|
||||
|
||||
@@ -17,6 +17,7 @@
|
||||
|
||||
package org.photonvision.common.hardware;
|
||||
|
||||
@SuppressWarnings("doclint")
|
||||
public enum VisionLEDMode {
|
||||
kDefault(-1),
|
||||
kOff(0),
|
||||
|
||||
@@ -40,6 +40,7 @@ import org.photonvision.targeting.PhotonPipelineResult;
|
||||
* <p>However, we do expect that the actual logic which fills out values in the entries will be
|
||||
* different for sim vs. real camera
|
||||
*/
|
||||
@SuppressWarnings("doclint")
|
||||
public class NTTopicSet {
|
||||
public NetworkTable subTable;
|
||||
|
||||
|
||||
@@ -25,6 +25,7 @@ import java.util.Set;
|
||||
import org.photonvision.common.dataflow.structures.Packet;
|
||||
import org.photonvision.common.dataflow.structures.PacketSerde;
|
||||
|
||||
@SuppressWarnings("doclint")
|
||||
public class PacketPublisher<T> implements AutoCloseable {
|
||||
public final RawPublisher publisher;
|
||||
private final PacketSerde<T> photonStruct;
|
||||
|
||||
@@ -23,6 +23,7 @@ import java.util.List;
|
||||
import org.photonvision.common.dataflow.structures.Packet;
|
||||
import org.photonvision.common.dataflow.structures.PacketSerde;
|
||||
|
||||
@SuppressWarnings("doclint")
|
||||
public class PacketSubscriber<T> implements AutoCloseable {
|
||||
public static class PacketResult<U> {
|
||||
public final U value;
|
||||
|
||||
@@ -22,6 +22,7 @@ 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. */
|
||||
@SuppressWarnings("doclint")
|
||||
public class CameraTargetRelation {
|
||||
public final Pose3d camPose;
|
||||
public final Transform3d camToTarg;
|
||||
|
||||
@@ -17,7 +17,6 @@
|
||||
|
||||
package org.photonvision.estimation;
|
||||
|
||||
import edu.wpi.first.cscore.OpenCvLoader;
|
||||
import edu.wpi.first.math.MatBuilder;
|
||||
import edu.wpi.first.math.Matrix;
|
||||
import edu.wpi.first.math.Nat;
|
||||
@@ -50,29 +49,39 @@ import org.opencv.imgproc.Imgproc;
|
||||
import org.photonvision.targeting.PnpResult;
|
||||
import org.photonvision.targeting.TargetCorner;
|
||||
|
||||
/**
|
||||
* A set of various utility functions for getting non-OpenCV data into an OpenCV-compatible format,
|
||||
* along with other calculation functions.
|
||||
*/
|
||||
public final class OpenCVHelp {
|
||||
private static final Rotation3d NWU_TO_EDN;
|
||||
private static final Rotation3d EDN_TO_NWU;
|
||||
|
||||
/**
|
||||
* @deprecated Replaced by {@link OpenCvLoader#forceStaticLoad()}
|
||||
*/
|
||||
@Deprecated(since = "2025", forRemoval = true)
|
||||
public static void forceLoadOpenCV() {
|
||||
OpenCvLoader.forceStaticLoad();
|
||||
}
|
||||
|
||||
static {
|
||||
NWU_TO_EDN = new Rotation3d(MatBuilder.fill(Nat.N3(), Nat.N3(), 0, -1, 0, 0, 0, -1, 1, 0, 0));
|
||||
EDN_TO_NWU = new Rotation3d(MatBuilder.fill(Nat.N3(), Nat.N3(), 0, 0, 1, -1, 0, 0, 0, -1, 0));
|
||||
}
|
||||
|
||||
private OpenCVHelp() {}
|
||||
|
||||
/**
|
||||
* Converts an EJML {@link SimpleMatrix} to OpenCV's {@link Mat} by copying the data.
|
||||
*
|
||||
* @param matrix The matrix of data.
|
||||
* @return The {@link Mat}. Data is encoded as 64-bit floats.
|
||||
*/
|
||||
public static Mat matrixToMat(SimpleMatrix matrix) {
|
||||
var mat = new Mat(matrix.getNumRows(), matrix.getNumCols(), CvType.CV_64F);
|
||||
mat.put(0, 0, matrix.getDDRM().getData());
|
||||
return mat;
|
||||
}
|
||||
|
||||
/**
|
||||
* Converts an OpenCV {@link Mat} to WPILib's {@link Matrix} by copying the data.
|
||||
*
|
||||
* @param mat The {@link Mat} of data. Data is assumed to be encoded as 64-bit floats.
|
||||
* @return The {@link Matrix}.
|
||||
*/
|
||||
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);
|
||||
@@ -82,10 +91,12 @@ public final class OpenCVHelp {
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates a new {@link MatOfPoint3f} with these 3d translations. The opencv tvec is a vector with
|
||||
* 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
|
||||
* @param translations The translations in the NWU coordinate system to convert into a
|
||||
* MatOfPoint3f
|
||||
* @return The OpenCV tvec.
|
||||
*/
|
||||
public static MatOfPoint3f translationToTvec(Translation3d... translations) {
|
||||
Point3[] points = new Point3[translations.length];
|
||||
@@ -97,10 +108,11 @@ public final class OpenCVHelp {
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns a new 3d translation from this {@link Mat}. The opencv tvec is a vector with three
|
||||
* 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
|
||||
* @return The 3d translation in the NWU coordinate system.
|
||||
*/
|
||||
public static Translation3d tvecToTranslation(Mat tvecInput) {
|
||||
float[] data = new float[3];
|
||||
@@ -112,11 +124,12 @@ public final class OpenCVHelp {
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates a new {@link MatOfPoint3f} with this 3d rotation. The opencv rvec Mat is a vector with
|
||||
* 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
|
||||
* @return The OpenCV rvec
|
||||
*/
|
||||
public static MatOfPoint3f rotationToRvec(Rotation3d rotation) {
|
||||
rotation = rotationNWUtoEDN(rotation);
|
||||
@@ -124,11 +137,12 @@ public final class OpenCVHelp {
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns a 3d rotation from this {@link Mat}. The opencv rvec Mat is a vector with three
|
||||
* 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
|
||||
* @return The 3d rotation
|
||||
*/
|
||||
public static Rotation3d rvecToRotation(Mat rvecInput) {
|
||||
// Get the 'rodriguez' (axis-angle, where the norm is the angle about the normalized direction
|
||||
@@ -142,6 +156,12 @@ public final class OpenCVHelp {
|
||||
return rotationEDNtoNWU(new Rotation3d(VecBuilder.fill(data[0], data[1], data[2])));
|
||||
}
|
||||
|
||||
/**
|
||||
* Calculates the average point from an array of points.
|
||||
*
|
||||
* @param points The array of points
|
||||
* @return The average of all the points
|
||||
*/
|
||||
public static Point avgPoint(Point[] points) {
|
||||
if (points == null || points.length == 0) return null;
|
||||
var pointMat = new MatOfPoint2f(points);
|
||||
@@ -151,6 +171,12 @@ public final class OpenCVHelp {
|
||||
return avgPt;
|
||||
}
|
||||
|
||||
/**
|
||||
* Converts a {@link TargetCorner} list to a {@link Point} array.
|
||||
*
|
||||
* @param corners The {@link TargetCorner} list
|
||||
* @return The {@link Point} array
|
||||
*/
|
||||
public static Point[] cornersToPoints(List<TargetCorner> corners) {
|
||||
var points = new Point[corners.size()];
|
||||
for (int i = 0; i < corners.size(); i++) {
|
||||
@@ -160,6 +186,12 @@ public final class OpenCVHelp {
|
||||
return points;
|
||||
}
|
||||
|
||||
/**
|
||||
* Converts a {@link TargetCorner} array to a {@link Point} array.
|
||||
*
|
||||
* @param corners The {@link TargetCorner} array
|
||||
* @return The {@link Point} array
|
||||
*/
|
||||
public static Point[] cornersToPoints(TargetCorner... corners) {
|
||||
var points = new Point[corners.length];
|
||||
for (int i = 0; i < corners.length; i++) {
|
||||
@@ -168,6 +200,12 @@ public final class OpenCVHelp {
|
||||
return points;
|
||||
}
|
||||
|
||||
/**
|
||||
* Converts a {@link Point} array to a {@link TargetCorner} list.
|
||||
*
|
||||
* @param points The {@link Point} array
|
||||
* @return The {@link TargetCorner} list
|
||||
*/
|
||||
public static List<TargetCorner> pointsToCorners(Point... points) {
|
||||
var corners = new ArrayList<TargetCorner>(points.length);
|
||||
for (Point point : points) {
|
||||
@@ -176,6 +214,12 @@ public final class OpenCVHelp {
|
||||
return corners;
|
||||
}
|
||||
|
||||
/**
|
||||
* Converts an OpenCV {@link MatOfPoint2f} to a {@link TargetCorner} list.
|
||||
*
|
||||
* @param matInput The Mat
|
||||
* @return The {@link TargetCorner} list
|
||||
*/
|
||||
public static List<TargetCorner> pointsToCorners(MatOfPoint2f matInput) {
|
||||
var corners = new ArrayList<TargetCorner>();
|
||||
float[] data = new float[(int) matInput.total() * matInput.channels()];
|
||||
@@ -220,6 +264,8 @@ public final class OpenCVHelp {
|
||||
/**
|
||||
* Convert a rotation delta from EDN to NWU. For example, if you have a rotation X,Y,Z {1, 0, 0}
|
||||
* in EDN, this would be {0, -1, 0} in NWU.
|
||||
*
|
||||
* @return The converted rotation in the NWU coordinate system
|
||||
*/
|
||||
private static Rotation3d rotationEDNtoNWU(Rotation3d rot) {
|
||||
return EDN_TO_NWU.unaryMinus().plus(rot.plus(EDN_TO_NWU));
|
||||
@@ -228,6 +274,8 @@ public final class OpenCVHelp {
|
||||
/**
|
||||
* Convert a rotation delta from NWU to EDN. For example, if you have a rotation X,Y,Z {1, 0, 0}
|
||||
* in NWU, this would be {0, 0, 1} in EDN.
|
||||
*
|
||||
* @return The converted rotation in the EDN coordinate system
|
||||
*/
|
||||
private static Rotation3d rotationNWUtoEDN(Rotation3d rot) {
|
||||
return NWU_TO_EDN.unaryMinus().plus(rot.plus(NWU_TO_EDN));
|
||||
@@ -236,6 +284,8 @@ public final class OpenCVHelp {
|
||||
/**
|
||||
* Convert a translation from EDN to NWU. For example, if you have a translation X,Y,Z {1, 0, 0}
|
||||
* in EDN, this would be {0, -1, 0} in NWU.
|
||||
*
|
||||
* @return The converted translation in the NWU coordinate system
|
||||
*/
|
||||
private static Translation3d translationEDNtoNWU(Translation3d trl) {
|
||||
return trl.rotateBy(EDN_TO_NWU);
|
||||
@@ -244,6 +294,8 @@ public final class OpenCVHelp {
|
||||
/**
|
||||
* Convert a translation from NWU to EDN. For example, if you have a translation X,Y,Z {1, 0, 0}
|
||||
* in NWU, this would be {0, 0, 1} in EDN.
|
||||
*
|
||||
* @return The converted translation in the EDN coordinate system
|
||||
*/
|
||||
private static Translation3d translationNWUtoEDN(Translation3d trl) {
|
||||
return trl.rotateBy(NWU_TO_EDN);
|
||||
@@ -256,6 +308,7 @@ public final class OpenCVHelp {
|
||||
* @param pointsList the undistorted points
|
||||
* @param cameraMatrix standard OpenCV camera mat
|
||||
* @param distCoeffs standard OpenCV distortion coefficients. Must OPENCV5 or OPENCV8
|
||||
* @return the list of distorted points
|
||||
*/
|
||||
public static List<Point> distortPoints(
|
||||
List<Point> pointsList, Mat cameraMatrix, Mat distCoeffs) {
|
||||
@@ -312,8 +365,8 @@ public final class OpenCVHelp {
|
||||
* 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 cameraMatrix the camera intrinsics matrix in standard OpenCV form
|
||||
* @param distCoeffs the camera distortion matrix in standard OpenCV form
|
||||
* @param camRt The change in basis from world coordinates to camera coordinates. See {@link
|
||||
* RotTrlTransform3d#makeRelativeTo(Pose3d)}.
|
||||
* @param objectTranslations The 3d points to be projected
|
||||
@@ -324,9 +377,9 @@ public final class OpenCVHelp {
|
||||
Matrix<N8, N1> distCoeffs,
|
||||
RotTrlTransform3d camRt,
|
||||
List<Translation3d> objectTranslations) {
|
||||
// translate to opencv classes
|
||||
// translate to OpenCV classes
|
||||
var objectPoints = translationToTvec(objectTranslations.toArray(new Translation3d[0]));
|
||||
// opencv rvec/tvec describe a change in basis from world to camera
|
||||
// OpenCV rvec/tvec describe a change in basis from world to camera
|
||||
var rvec = rotationToRvec(camRt.getRotation());
|
||||
var tvec = translationToTvec(camRt.getTranslation());
|
||||
var cameraMatrixMat = matrixToMat(cameraMatrix.getStorage());
|
||||
@@ -354,8 +407,8 @@ public final class OpenCVHelp {
|
||||
* 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 cameraMatrix The camera intrinsics matrix in standard OpenCV form
|
||||
* @param distCoeffs The camera distortion matrix in standard OpenCV form
|
||||
* @param points The distorted image points
|
||||
* @return The undistorted image points
|
||||
*/
|
||||
@@ -444,8 +497,8 @@ public final class OpenCVHelp {
|
||||
* <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 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>
|
||||
@@ -479,7 +532,7 @@ public final class OpenCVHelp {
|
||||
// IPPE_SQUARE expects our corners in a specific order
|
||||
modelTrls = reorderCircular(modelTrls, true, -1);
|
||||
imagePoints = reorderCircular(Arrays.asList(imagePoints), true, -1).toArray(Point[]::new);
|
||||
// translate to opencv classes
|
||||
// translate to OpenCV classes
|
||||
translationToTvec(modelTrls.toArray(new Translation3d[0])).assignTo(objectMat);
|
||||
imageMat.fromArray(imagePoints);
|
||||
matrixToMat(cameraMatrix.getStorage()).assignTo(cameraMatrixMat);
|
||||
@@ -559,8 +612,8 @@ public final class OpenCVHelp {
|
||||
* solution-- if you are intending to use solvePNP on a single AprilTag, see {@link
|
||||
* #solvePNP_SQUARE} instead.
|
||||
*
|
||||
* @param cameraMatrix The camera intrinsics matrix in standard opencv form
|
||||
* @param distCoeffs The camera distortion matrix in standard opencv form
|
||||
* @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 imagePoints The projection of these 3d object points into the 2d camera image. The order
|
||||
* should match the given object point translations.
|
||||
@@ -574,7 +627,7 @@ public final class OpenCVHelp {
|
||||
List<Translation3d> objectTrls,
|
||||
Point[] imagePoints) {
|
||||
try {
|
||||
// translate to opencv classes
|
||||
// translate to OpenCV classes
|
||||
MatOfPoint3f objectMat = translationToTvec(objectTrls.toArray(new Translation3d[0]));
|
||||
MatOfPoint2f imageMat = new MatOfPoint2f(imagePoints);
|
||||
Mat cameraMatrixMat = matrixToMat(cameraMatrix.getStorage());
|
||||
|
||||
@@ -62,6 +62,7 @@ public class RotTrlTransform3d {
|
||||
this(trf.getRotation(), trf.getTranslation());
|
||||
}
|
||||
|
||||
/** Constructs the identity transform -- maps an initial pose to itself. */
|
||||
public RotTrlTransform3d() {
|
||||
this(new Rotation3d(), new Translation3d());
|
||||
}
|
||||
@@ -76,24 +77,40 @@ public class RotTrlTransform3d {
|
||||
return new RotTrlTransform3d(pose.getRotation(), pose.getTranslation()).inverse();
|
||||
}
|
||||
|
||||
/** The inverse of this transformation. Applying the inverse will "undo" this transformation. */
|
||||
/**
|
||||
* The inverse of this transformation. Applying the inverse will "undo" this transformation.
|
||||
*
|
||||
* @return The inverse 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) */
|
||||
/**
|
||||
* This transformation as a Transform3d (as if of the origin)
|
||||
*
|
||||
* @return The Transform2d
|
||||
*/
|
||||
public Transform3d getTransform() {
|
||||
return new Transform3d(trl, rot);
|
||||
}
|
||||
|
||||
/** The translation component of this transformation */
|
||||
/**
|
||||
* The translation component of this transformation
|
||||
*
|
||||
* @return The Translation3d
|
||||
*/
|
||||
public Translation3d getTranslation() {
|
||||
return trl;
|
||||
}
|
||||
|
||||
/** The rotation component of this transformation */
|
||||
/**
|
||||
* The rotation component of this transformation
|
||||
*
|
||||
* @return The Rotation3d
|
||||
*/
|
||||
public Rotation3d getRotation() {
|
||||
return rot;
|
||||
}
|
||||
|
||||
@@ -34,11 +34,19 @@ public class TargetModel {
|
||||
*/
|
||||
public final List<Translation3d> vertices;
|
||||
|
||||
/** True if the target is planar, like an AprilTag. False otherwise. */
|
||||
public final boolean isPlanar;
|
||||
|
||||
/** True if the target is spherical, like a ball. False otherwise. */
|
||||
public final boolean isSpherical;
|
||||
|
||||
/** The model of AprilTags in the 16h5 family used by <i>FIRST</i> in FRC 2023. */
|
||||
public static final TargetModel kAprilTag16h5 =
|
||||
new TargetModel(Units.inchesToMeters(6), Units.inchesToMeters(6));
|
||||
|
||||
/**
|
||||
* The model of AprilTags in the 36h11 family used by <i>FIRST</i> in FRC 2024 and later years.
|
||||
*/
|
||||
public static final TargetModel kAprilTag36h11 =
|
||||
new TargetModel(Units.inchesToMeters(6.5), Units.inchesToMeters(6.5));
|
||||
|
||||
@@ -148,6 +156,9 @@ public class TargetModel {
|
||||
*
|
||||
* <p>Note: If this target is spherical, use {@link #getOrientedPose(Translation3d,
|
||||
* Translation3d)} with this method.
|
||||
*
|
||||
* @param targetPose The field pose to offset the vertices by.
|
||||
* @return The list of vertices offset from the target pose.
|
||||
*/
|
||||
public List<Translation3d> getFieldVertices(Pose3d targetPose) {
|
||||
var basisChange = new RotTrlTransform3d(targetPose.getRotation(), targetPose.getTranslation());
|
||||
|
||||
@@ -45,7 +45,15 @@ import org.photonvision.targeting.PnpResult;
|
||||
import org.photonvision.targeting.TargetCorner;
|
||||
|
||||
public class VisionEstimation {
|
||||
/** Get the visible {@link AprilTag}s which are in the tag layout using the visible tag IDs. */
|
||||
private VisionEstimation() {}
|
||||
|
||||
/**
|
||||
* Get the list of visible {@link AprilTag}s which are in the tag layout using the visible tag
|
||||
* IDs.
|
||||
*
|
||||
* @param visTags The list of targets to search for visible tags.
|
||||
* @param tagLayout The tag layout to search
|
||||
*/
|
||||
public static List<AprilTag> getVisibleLayoutTags(
|
||||
List<PhotonTrackedTarget> visTags, AprilTagFieldLayout tagLayout) {
|
||||
return visTags.stream()
|
||||
@@ -74,6 +82,7 @@ public class VisionEstimation {
|
||||
* @param distCoeffs The camera distortion matrix in standard opencv form
|
||||
* @param visTags The visible tags reported by PV. Non-tag targets are automatically excluded.
|
||||
* @param tagLayout The known tag layout on the field
|
||||
* @param tagModel The model describing the tag's geometry
|
||||
* @return The transformation that maps the field origin to the camera pose. Ensure the {@link
|
||||
* PnpResult} are present before utilizing them.
|
||||
*/
|
||||
|
||||
@@ -30,8 +30,11 @@ public class MultiTargetPNPResult
|
||||
private static final int MAX_IDS = 32;
|
||||
|
||||
public PnpResult estimatedPose = new PnpResult();
|
||||
|
||||
/** The fiducial IDs used to calculate this multi-target result. */
|
||||
public List<Short> fiducialIDsUsed = List.of();
|
||||
|
||||
/** Used for serialization and tests. */
|
||||
public MultiTargetPNPResult() {}
|
||||
|
||||
public MultiTargetPNPResult(PnpResult results, List<Short> ids) {
|
||||
@@ -72,9 +75,10 @@ public class MultiTargetPNPResult
|
||||
+ "]";
|
||||
}
|
||||
|
||||
/** MultiTargetPNPResult protobuf for serialization. */
|
||||
public static final MultiTargetPNPResultProto proto = new MultiTargetPNPResultProto();
|
||||
|
||||
// tODO!
|
||||
/** MultiTargetPNPResult PhotonStruct for serialization. */
|
||||
public static final MultiTargetPNPResultSerde photonStruct = new MultiTargetPNPResultSerde();
|
||||
|
||||
@Override
|
||||
|
||||
@@ -48,17 +48,29 @@ public class PhotonPipelineMetadata implements PhotonStructSerializable<PhotonPi
|
||||
this(-1, -1, -1, Long.MAX_VALUE);
|
||||
}
|
||||
|
||||
/** Returns the time between image capture and publish to NT */
|
||||
/**
|
||||
* Returns the time between image capture and publish to NT
|
||||
*
|
||||
* @return The time in milliseconds
|
||||
*/
|
||||
public double getLatencyMillis() {
|
||||
return (publishTimestampMicros - captureTimestampMicros) / 1e3;
|
||||
}
|
||||
|
||||
/** The time that this image was captured, in the coprocessor's time base. */
|
||||
/**
|
||||
* The time that this image was captured, in the coprocessor's time base.
|
||||
*
|
||||
* @return The time in microseconds
|
||||
*/
|
||||
public long getCaptureTimestampMicros() {
|
||||
return captureTimestampMicros;
|
||||
}
|
||||
|
||||
/** The time that this result was published to NT, in the coprocessor's time base. */
|
||||
/**
|
||||
* The time that this result was published to NT, in the coprocessor's time base.
|
||||
*
|
||||
* @return The time in microseconds
|
||||
*/
|
||||
public long getPublishTimestampMicros() {
|
||||
return publishTimestampMicros;
|
||||
}
|
||||
@@ -66,6 +78,8 @@ public class PhotonPipelineMetadata implements PhotonStructSerializable<PhotonPi
|
||||
/**
|
||||
* The number of non-empty frames processed by this camera since boot. Useful to checking if a
|
||||
* camera is alive.
|
||||
*
|
||||
* @return The number of non-empty frames
|
||||
*/
|
||||
public long getSequenceID() {
|
||||
return sequenceID;
|
||||
|
||||
@@ -31,13 +31,13 @@ public class PhotonPipelineResult
|
||||
implements ProtobufSerializable, PhotonStructSerializable<PhotonPipelineResult> {
|
||||
private static boolean HAS_WARNED = false;
|
||||
|
||||
// Frame capture metadata
|
||||
/** Frame capture metadata. */
|
||||
public PhotonPipelineMetadata metadata;
|
||||
|
||||
// Targets to store.
|
||||
/** The list of targets detected by the pipeline. */
|
||||
public List<PhotonTrackedTarget> targets = new ArrayList<>();
|
||||
|
||||
// Multi-tag result
|
||||
/** The multitag result, if using an AprilTag pipeline with Multi-Target Estimation enabled. */
|
||||
public Optional<MultiTargetPNPResult> multitagResult;
|
||||
|
||||
/** Constructs an empty pipeline result. */
|
||||
@@ -53,6 +53,7 @@ public class PhotonPipelineResult
|
||||
* coprocessor captured the image this result contains the targeting info of
|
||||
* @param publishTimestampMicros The time, in uS in the coprocessor's timebase, that the
|
||||
* coprocessor published targeting info
|
||||
* @param timeSinceLastPong The time since the last Time Sync Pong in uS.
|
||||
* @param targets The list of targets identified by the pipeline.
|
||||
*/
|
||||
public PhotonPipelineResult(
|
||||
@@ -76,6 +77,7 @@ public class PhotonPipelineResult
|
||||
* captured the image this result contains the targeting info of
|
||||
* @param publishTimestamp The time, in uS in the coprocessor's timebase, that the coprocessor
|
||||
* published targeting info
|
||||
* @param timeSinceLastPong The time since the last Time Sync Pong in uS.
|
||||
* @param targets The list of targets identified by the pipeline.
|
||||
* @param result Result from multi-target PNP.
|
||||
*/
|
||||
@@ -155,8 +157,11 @@ public class PhotonPipelineResult
|
||||
}
|
||||
|
||||
/**
|
||||
* Return the latest multi-target result. Be sure to check
|
||||
* getMultiTagResult().estimatedPose.isPresent before using the pose estimate!
|
||||
* Return the latest multi-target result. Be sure to check {@code getMultiTagResult().isPresent()}
|
||||
* before using the pose estimate!
|
||||
*
|
||||
* @return The multi-target result. Empty if there's no multi-target result/Multi-Target
|
||||
* Estimation is disabled in the UI.
|
||||
*/
|
||||
public Optional<MultiTargetPNPResult> getMultiTagResult() {
|
||||
return multitagResult;
|
||||
@@ -212,7 +217,10 @@ public class PhotonPipelineResult
|
||||
return true;
|
||||
}
|
||||
|
||||
/** PhotonPipelineResult PhotonStruct for serialization. */
|
||||
public static final PhotonPipelineResultSerde photonStruct = new PhotonPipelineResultSerde();
|
||||
|
||||
/** PhotonPipelineResult Protobuf for serialization. */
|
||||
public static final PhotonPipelineResultProto proto = new PhotonPipelineResultProto();
|
||||
|
||||
@Override
|
||||
|
||||
@@ -25,28 +25,63 @@ import org.photonvision.struct.PhotonTrackedTargetSerde;
|
||||
import org.photonvision.targeting.proto.PhotonTrackedTargetProto;
|
||||
import org.photonvision.targeting.serde.PhotonStructSerializable;
|
||||
|
||||
/** Information about a detected target. */
|
||||
public class PhotonTrackedTarget
|
||||
implements ProtobufSerializable, PhotonStructSerializable<PhotonTrackedTarget> {
|
||||
private static final int MAX_CORNERS = 8;
|
||||
|
||||
/** The yaw of the target in degrees, with left being the positive direction. */
|
||||
public double yaw;
|
||||
|
||||
/** The pitch of the target in degrees, with up being the positive direction. */
|
||||
public double pitch;
|
||||
|
||||
/** The area (how much of the camera feed the bounding box takes up) as a percentage (0-100). */
|
||||
public double area;
|
||||
|
||||
/** The skew of the target in degrees, with counterclockwise being the positive direction. */
|
||||
public double skew;
|
||||
|
||||
/** The fiducial ID, or -1 if it doesn't exist for this target. */
|
||||
public int fiducialId;
|
||||
|
||||
/** The object detection class ID, or -1 if it doesn't exist for this target. */
|
||||
public int objDetectId;
|
||||
|
||||
/** The object detection confidence, or -1 if it doesn't exist for this target. */
|
||||
public float objDetectConf;
|
||||
|
||||
/** The transform with the lowest reprojection error */
|
||||
public Transform3d bestCameraToTarget;
|
||||
|
||||
/** The transform with the highest reprojection error */
|
||||
public Transform3d altCameraToTarget;
|
||||
|
||||
/** The ratio (best:alt) of reprojection errors */
|
||||
public double poseAmbiguity;
|
||||
|
||||
// Corners from the min-area rectangle bounding the target
|
||||
/** Corners from the min-area rectangle bounding the target */
|
||||
public List<TargetCorner> minAreaRectCorners;
|
||||
|
||||
// Corners from whatever corner detection method was used
|
||||
/** Corners from the corner detection method used */
|
||||
public List<TargetCorner> detectedCorners;
|
||||
|
||||
/** Construct a tracked target, given exactly 4 corners */
|
||||
/**
|
||||
* Construct a tracked target, given exactly 4 corners
|
||||
*
|
||||
* @param yaw The yaw of the target
|
||||
* @param pitch The pitch of the target
|
||||
* @param area The area of the target as a percentage of the camera image
|
||||
* @param skew The skew of the target
|
||||
* @param fiducialId The fiduical tag ID
|
||||
* @param classId The object detection class ID
|
||||
* @param objDetectConf The object detection confidence
|
||||
* @param pose The best camera to target transform
|
||||
* @param altPose The alternate camera to target transform
|
||||
* @param ambiguity The ambiguity (best:alternate ratio of reprojection errors) of the target
|
||||
* @param minAreaRectCorners The corners of minimum area bounding box of the target
|
||||
* @param detectedCorners The detected corners of the target
|
||||
*/
|
||||
public PhotonTrackedTarget(
|
||||
double yaw,
|
||||
double pitch,
|
||||
@@ -80,9 +115,8 @@ public class PhotonTrackedTarget
|
||||
this.poseAmbiguity = ambiguity;
|
||||
}
|
||||
|
||||
public PhotonTrackedTarget() {
|
||||
// TODO Auto-generated constructor stub
|
||||
}
|
||||
/** Used for serialization. */
|
||||
public PhotonTrackedTarget() {}
|
||||
|
||||
public double getYaw() {
|
||||
return yaw;
|
||||
@@ -92,6 +126,11 @@ public class PhotonTrackedTarget
|
||||
return pitch;
|
||||
}
|
||||
|
||||
/**
|
||||
* The area (how much of the camera feed the bounding box takes up) as a percentage (0-100).
|
||||
*
|
||||
* @return The area as a percentage
|
||||
*/
|
||||
public double getArea() {
|
||||
return area;
|
||||
}
|
||||
@@ -100,19 +139,29 @@ public class PhotonTrackedTarget
|
||||
return skew;
|
||||
}
|
||||
|
||||
/** Get the fiducial ID, or -1 if not set. */
|
||||
/**
|
||||
* Get the fiducial ID, or -1 if it doesn't exist for this target.
|
||||
*
|
||||
* @return The fiducial ID
|
||||
*/
|
||||
public int getFiducialId() {
|
||||
return fiducialId;
|
||||
}
|
||||
|
||||
/** Get the object detection class ID number, or -1 if not set. */
|
||||
/**
|
||||
* Get the object detection class ID number, or -1 if it doesn't exist for this target.
|
||||
*
|
||||
* @return The object detection class ID
|
||||
*/
|
||||
public int getDetectedObjectClassID() {
|
||||
return objDetectId;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the object detection confidence, or -1 if not set. This will be between 0 and 1, with 1
|
||||
* indicating most confidence, and 0 least.
|
||||
* Get the object detection confidence, or -1 if it doesn't exist for this target. This will be
|
||||
* between 0 and 1, with 1 indicating most confidence, and 0 least.
|
||||
*
|
||||
* @return The object detection confidence
|
||||
*/
|
||||
public float getDetectedObjectConfidence() {
|
||||
return objDetectConf;
|
||||
@@ -122,6 +171,8 @@ public class PhotonTrackedTarget
|
||||
* Get the ratio of best:alternate pose reprojection errors, called ambiguity. This is between 0
|
||||
* and 1 (0 being no ambiguity, and 1 meaning both have the same reprojection error). Numbers
|
||||
* above 0.2 are likely to be ambiguous. -1 if invalid.
|
||||
*
|
||||
* @return The pose ambiguity
|
||||
*/
|
||||
public double getPoseAmbiguity() {
|
||||
return poseAmbiguity;
|
||||
@@ -130,6 +181,8 @@ public class PhotonTrackedTarget
|
||||
/**
|
||||
* Return a list of the 4 corners in image space (origin top left, x right, y down), in no
|
||||
* particular order, of the minimum area bounding rectangle of this target
|
||||
*
|
||||
* @return The list of corners
|
||||
*/
|
||||
public List<TargetCorner> getMinAreaRectCorners() {
|
||||
return minAreaRectCorners;
|
||||
@@ -147,6 +200,8 @@ public class PhotonTrackedTarget
|
||||
* V | |
|
||||
* +Y 0 ----- 1
|
||||
* </pre>
|
||||
*
|
||||
* @return The list of detected corners for this target
|
||||
*/
|
||||
public List<TargetCorner> getDetectedCorners() {
|
||||
return detectedCorners;
|
||||
@@ -155,6 +210,8 @@ public class PhotonTrackedTarget
|
||||
/**
|
||||
* Get the transform that maps camera space (X = forward, Y = left, Z = up) to object/fiducial tag
|
||||
* space (X forward, Y left, Z up) with the lowest reprojection error
|
||||
*
|
||||
* @return The transform with the lowest reprojection error (the best)
|
||||
*/
|
||||
public Transform3d getBestCameraToTarget() {
|
||||
return bestCameraToTarget;
|
||||
@@ -163,6 +220,8 @@ public class PhotonTrackedTarget
|
||||
/**
|
||||
* Get the transform that maps camera space (X = forward, Y = left, Z = up) to object/fiducial tag
|
||||
* space (X forward, Y left, Z up) with the highest reprojection error
|
||||
*
|
||||
* @return The transform with the highest reprojection error (the alternate)
|
||||
*/
|
||||
public Transform3d getAlternateCameraToTarget() {
|
||||
return altCameraToTarget;
|
||||
@@ -253,7 +312,10 @@ public class PhotonTrackedTarget
|
||||
+ "]";
|
||||
}
|
||||
|
||||
/** PhotonTrackedTarget protobuf for serialization. */
|
||||
public static final PhotonTrackedTargetProto proto = new PhotonTrackedTargetProto();
|
||||
|
||||
/** PhotonTrackedTarget PhotonStruct for serialization. */
|
||||
public static final PhotonTrackedTargetSerde photonStruct = new PhotonTrackedTargetSerde();
|
||||
|
||||
@Override
|
||||
|
||||
@@ -33,6 +33,7 @@ import org.photonvision.targeting.serde.PhotonStructSerializable;
|
||||
* <p>Note that the coordinate frame of these transforms depends on the implementing solvePnP
|
||||
* method.
|
||||
*/
|
||||
@SuppressWarnings("doclint")
|
||||
public class PnpResult implements ProtobufSerializable, PhotonStructSerializable<PnpResult> {
|
||||
/**
|
||||
* The best-fit transform. The coordinate frame of this transform depends on the method which gave
|
||||
@@ -133,7 +134,10 @@ public class PnpResult implements ProtobufSerializable, PhotonStructSerializable
|
||||
+ "]";
|
||||
}
|
||||
|
||||
/** PnpResult protobuf for serialization. */
|
||||
public static final PNPResultProto proto = new PNPResultProto();
|
||||
|
||||
/** PnpResult PhotonStruct for serialization. */
|
||||
public static final PnpResultSerde photonStruct = new PnpResultSerde();
|
||||
|
||||
@Override
|
||||
|
||||
@@ -28,6 +28,7 @@ import org.photonvision.targeting.serde.PhotonStructSerializable;
|
||||
* Represents a point in an image at the corner of the minimum-area bounding rectangle, in pixels.
|
||||
* Origin at the top left, plus-x to the right, plus-y down.
|
||||
*/
|
||||
@SuppressWarnings("doclint")
|
||||
public class TargetCorner implements ProtobufSerializable, PhotonStructSerializable<TargetCorner> {
|
||||
public double x;
|
||||
public double y;
|
||||
@@ -59,7 +60,10 @@ public class TargetCorner implements ProtobufSerializable, PhotonStructSerializa
|
||||
return "(" + x + "," + y + ')';
|
||||
}
|
||||
|
||||
/** TargetCorner protobuf for serialization. */
|
||||
public static final TargetCornerProto proto = new TargetCornerProto();
|
||||
|
||||
/** TargetCorner PhotonStruct for serialization. */
|
||||
public static final TargetCornerSerde photonStruct = new TargetCornerSerde();
|
||||
|
||||
@Override
|
||||
|
||||
@@ -20,5 +20,10 @@ package org.photonvision.targeting.serde;
|
||||
import org.photonvision.common.dataflow.structures.PacketSerde;
|
||||
|
||||
public interface PhotonStructSerializable<T> {
|
||||
/**
|
||||
* Returns the PhotonStruct serializer for this type.
|
||||
*
|
||||
* @return The PhotonStruct serializer
|
||||
*/
|
||||
PacketSerde<T> getSerde();
|
||||
}
|
||||
|
||||
@@ -20,6 +20,7 @@ package org.photonvision.utils;
|
||||
import edu.wpi.first.math.geometry.*;
|
||||
import org.photonvision.common.dataflow.structures.Packet;
|
||||
|
||||
@SuppressWarnings("doclint")
|
||||
public class PacketUtils {
|
||||
public static final int ROTATION2D_BYTE_SIZE = Double.BYTES;
|
||||
public static final int QUATERNION_BYTE_SIZE = Double.BYTES * 4;
|
||||
|
||||
Reference in New Issue
Block a user