001/*
002 * Copyright (C) Photon Vision.
003 *
004 * This program is free software: you can redistribute it and/or modify
005 * it under the terms of the GNU General Public License as published by
006 * the Free Software Foundation, either version 3 of the License, or
007 * (at your option) any later version.
008 *
009 * This program is distributed in the hope that it will be useful,
010 * but WITHOUT ANY WARRANTY; without even the implied warranty of
011 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
012 * GNU General Public License for more details.
013 *
014 * You should have received a copy of the GNU General Public License
015 * along with this program.  If not, see <https://www.gnu.org/licenses/>.
016 */
017
018package org.photonvision.estimation;
019
020import edu.wpi.first.math.MatBuilder;
021import edu.wpi.first.math.Matrix;
022import edu.wpi.first.math.Nat;
023import edu.wpi.first.math.Num;
024import edu.wpi.first.math.VecBuilder;
025import edu.wpi.first.math.geometry.Pose3d;
026import edu.wpi.first.math.geometry.Rotation3d;
027import edu.wpi.first.math.geometry.Transform3d;
028import edu.wpi.first.math.geometry.Translation3d;
029import edu.wpi.first.math.numbers.*;
030import java.util.ArrayList;
031import java.util.Arrays;
032import java.util.List;
033import java.util.Optional;
034import org.ejml.simple.SimpleMatrix;
035import org.opencv.calib3d.Calib3d;
036import org.opencv.core.Core;
037import org.opencv.core.CvType;
038import org.opencv.core.Mat;
039import org.opencv.core.MatOfDouble;
040import org.opencv.core.MatOfInt;
041import org.opencv.core.MatOfPoint;
042import org.opencv.core.MatOfPoint2f;
043import org.opencv.core.MatOfPoint3f;
044import org.opencv.core.Point;
045import org.opencv.core.Point3;
046import org.opencv.core.Rect;
047import org.opencv.core.RotatedRect;
048import org.opencv.imgproc.Imgproc;
049import org.photonvision.targeting.PnpResult;
050import org.photonvision.targeting.TargetCorner;
051
052/**
053 * A set of various utility functions for getting non-OpenCV data into an OpenCV-compatible format,
054 * along with other calculation functions.
055 */
056public final class OpenCVHelp {
057    private static final Rotation3d NWU_TO_EDN;
058    private static final Rotation3d EDN_TO_NWU;
059
060    static {
061        NWU_TO_EDN = new Rotation3d(MatBuilder.fill(Nat.N3(), Nat.N3(), 0, -1, 0, 0, 0, -1, 1, 0, 0));
062        EDN_TO_NWU = new Rotation3d(MatBuilder.fill(Nat.N3(), Nat.N3(), 0, 0, 1, -1, 0, 0, 0, -1, 0));
063    }
064
065    private OpenCVHelp() {}
066
067    /**
068     * Converts an EJML {@link SimpleMatrix} to OpenCV's {@link Mat} by copying the data.
069     *
070     * @param matrix The matrix of data.
071     * @return The {@link Mat}. Data is encoded as 64-bit floats.
072     */
073    public static Mat matrixToMat(SimpleMatrix matrix) {
074        var mat = new Mat(matrix.getNumRows(), matrix.getNumCols(), CvType.CV_64F);
075        mat.put(0, 0, matrix.getDDRM().getData());
076        return mat;
077    }
078
079    /**
080     * Converts an OpenCV {@link Mat} to WPILib's {@link Matrix} by copying the data.
081     *
082     * @param mat The {@link Mat} of data. Data is assumed to be encoded as 64-bit floats.
083     * @return The {@link Matrix}.
084     */
085    public static Matrix<Num, Num> matToMatrix(Mat mat) {
086        double[] data = new double[(int) mat.total() * mat.channels()];
087        var doubleMat = new Mat(mat.rows(), mat.cols(), CvType.CV_64F);
088        mat.convertTo(doubleMat, CvType.CV_64F);
089        doubleMat.get(0, 0, data);
090        return new Matrix<>(new SimpleMatrix(mat.rows(), mat.cols(), true, data));
091    }
092
093    /**
094     * Creates a new {@link MatOfPoint3f} with these 3d translations. The OpenCV tvec is a vector with
095     * three elements representing {x, y, z} in the EDN coordinate system.
096     *
097     * @param translations The translations in the NWU coordinate system to convert into a
098     *     MatOfPoint3f
099     * @return The OpenCV tvec.
100     */
101    public static MatOfPoint3f translationToTvec(Translation3d... translations) {
102        Point3[] points = new Point3[translations.length];
103        for (int i = 0; i < translations.length; i++) {
104            var trl = translationNWUtoEDN(translations[i]);
105            points[i] = new Point3(trl.getX(), trl.getY(), trl.getZ());
106        }
107        return new MatOfPoint3f(points);
108    }
109
110    /**
111     * Returns a new 3d translation from this {@link Mat}. The OpenCV tvec is a vector with three
112     * elements representing {x, y, z} in the EDN coordinate system.
113     *
114     * @param tvecInput The tvec to create a Translation3d from
115     * @return The 3d translation in the NWU coordinate system.
116     */
117    public static Translation3d tvecToTranslation(Mat tvecInput) {
118        float[] data = new float[3];
119        var wrapped = new Mat(tvecInput.rows(), tvecInput.cols(), CvType.CV_32F);
120        tvecInput.convertTo(wrapped, CvType.CV_32F);
121        wrapped.get(0, 0, data);
122        wrapped.release();
123        return translationEDNtoNWU(new Translation3d(data[0], data[1], data[2]));
124    }
125
126    /**
127     * Creates a new {@link MatOfPoint3f} with this 3d rotation. The OpenCV rvec Mat is a vector with
128     * three elements representing the axis scaled by the angle in the EDN coordinate system. (angle =
129     * norm, and axis = rvec / norm)
130     *
131     * @param rotation The rotation to convert into a MatOfPoint3f
132     * @return The OpenCV rvec
133     */
134    public static MatOfPoint3f rotationToRvec(Rotation3d rotation) {
135        rotation = rotationNWUtoEDN(rotation);
136        return new MatOfPoint3f(new Point3(rotation.getQuaternion().toRotationVector().getData()));
137    }
138
139    /**
140     * Returns a 3d rotation from this {@link Mat}. The OpenCV rvec Mat is a vector with three
141     * elements representing the axis scaled by the angle in the EDN coordinate system. (angle = norm,
142     * and axis = rvec / norm)
143     *
144     * @param rvecInput The rvec to create a Rotation3d from
145     * @return The 3d rotation
146     */
147    public static Rotation3d rvecToRotation(Mat rvecInput) {
148        // Get the 'rodriguez' (axis-angle, where the norm is the angle about the normalized direction
149        // of the vector)
150        float[] data = new float[3];
151        var wrapped = new Mat(rvecInput.rows(), rvecInput.cols(), CvType.CV_32F);
152        rvecInput.convertTo(wrapped, CvType.CV_32F);
153        wrapped.get(0, 0, data);
154        wrapped.release();
155
156        return rotationEDNtoNWU(new Rotation3d(VecBuilder.fill(data[0], data[1], data[2])));
157    }
158
159    /**
160     * Calculates the average point from an array of points.
161     *
162     * @param points The array of points
163     * @return The average of all the points
164     */
165    public static Point avgPoint(Point[] points) {
166        if (points == null || points.length == 0) return null;
167        var pointMat = new MatOfPoint2f(points);
168        Core.reduce(pointMat, pointMat, 0, Core.REDUCE_AVG);
169        var avgPt = pointMat.toArray()[0];
170        pointMat.release();
171        return avgPt;
172    }
173
174    /**
175     * Converts a {@link TargetCorner} list to a {@link Point} array.
176     *
177     * @param corners The {@link TargetCorner} list
178     * @return The {@link Point} array
179     */
180    public static Point[] cornersToPoints(List<TargetCorner> corners) {
181        var points = new Point[corners.size()];
182        for (int i = 0; i < corners.size(); i++) {
183            var corn = corners.get(i);
184            points[i] = new Point(corn.x, corn.y);
185        }
186        return points;
187    }
188
189    /**
190     * Converts a {@link TargetCorner} array to a {@link Point} array.
191     *
192     * @param corners The {@link TargetCorner} array
193     * @return The {@link Point} array
194     */
195    public static Point[] cornersToPoints(TargetCorner... corners) {
196        var points = new Point[corners.length];
197        for (int i = 0; i < corners.length; i++) {
198            points[i] = new Point(corners[i].x, corners[i].y);
199        }
200        return points;
201    }
202
203    /**
204     * Converts a {@link Point} array to a {@link TargetCorner} list.
205     *
206     * @param points The {@link Point} array
207     * @return The {@link TargetCorner} list
208     */
209    public static List<TargetCorner> pointsToCorners(Point... points) {
210        var corners = new ArrayList<TargetCorner>(points.length);
211        for (Point point : points) {
212            corners.add(new TargetCorner(point.x, point.y));
213        }
214        return corners;
215    }
216
217    /**
218     * Converts an OpenCV {@link MatOfPoint2f} to a {@link TargetCorner} list.
219     *
220     * @param matInput The Mat
221     * @return The {@link TargetCorner} list
222     */
223    public static List<TargetCorner> pointsToCorners(MatOfPoint2f matInput) {
224        var corners = new ArrayList<TargetCorner>();
225        float[] data = new float[(int) matInput.total() * matInput.channels()];
226        matInput.get(0, 0, data);
227        for (int i = 0; i < (int) matInput.total(); i++) {
228            corners.add(new TargetCorner(data[0 + 2 * i], data[1 + 2 * i]));
229        }
230        return corners;
231    }
232
233    /**
234     * Reorders the list, optionally indexing backwards and wrapping around to the last element after
235     * the first, and shifting all indices in the direction of indexing.
236     *
237     * <p>e.g.
238     *
239     * <p>({1,2,3}, false, 1) == {2,3,1}
240     *
241     * <p>({1,2,3}, true, 0) == {1,3,2}
242     *
243     * <p>({1,2,3}, true, 1) == {3,2,1}
244     *
245     * @param <T> Element type
246     * @param elements list elements
247     * @param backwards If indexing should happen in reverse (0, size-1, size-2, ...)
248     * @param shiftStart How much the initial index should be shifted (instead of starting at index 0,
249     *     start at shiftStart, negated if backwards)
250     * @return Reordered list
251     */
252    public static <T> List<T> reorderCircular(List<T> elements, boolean backwards, int shiftStart) {
253        int size = elements.size();
254        int dir = backwards ? -1 : 1;
255        var reordered = new ArrayList<>(elements);
256        for (int i = 0; i < size; i++) {
257            int index = (i * dir + shiftStart * dir) % size;
258            if (index < 0) index = size + index;
259            reordered.set(i, elements.get(index));
260        }
261        return reordered;
262    }
263
264    /**
265     * Convert a rotation delta from EDN to NWU. For example, if you have a rotation X,Y,Z {1, 0, 0}
266     * in EDN, this would be {0, -1, 0} in NWU.
267     *
268     * @return The converted rotation in the NWU coordinate system
269     */
270    private static Rotation3d rotationEDNtoNWU(Rotation3d rot) {
271        return EDN_TO_NWU.unaryMinus().plus(rot.plus(EDN_TO_NWU));
272    }
273
274    /**
275     * Convert a rotation delta from NWU to EDN. For example, if you have a rotation X,Y,Z {1, 0, 0}
276     * in NWU, this would be {0, 0, 1} in EDN.
277     *
278     * @return The converted rotation in the EDN coordinate system
279     */
280    private static Rotation3d rotationNWUtoEDN(Rotation3d rot) {
281        return NWU_TO_EDN.unaryMinus().plus(rot.plus(NWU_TO_EDN));
282    }
283
284    /**
285     * Convert a translation from EDN to NWU. For example, if you have a translation X,Y,Z {1, 0, 0}
286     * in EDN, this would be {0, -1, 0} in NWU.
287     *
288     * @return The converted translation in the NWU coordinate system
289     */
290    private static Translation3d translationEDNtoNWU(Translation3d trl) {
291        return trl.rotateBy(EDN_TO_NWU);
292    }
293
294    /**
295     * Convert a translation from NWU to EDN. For example, if you have a translation X,Y,Z {1, 0, 0}
296     * in NWU, this would be {0, 0, 1} in EDN.
297     *
298     * @return The converted translation in the EDN coordinate system
299     */
300    private static Translation3d translationNWUtoEDN(Translation3d trl) {
301        return trl.rotateBy(NWU_TO_EDN);
302    }
303
304    /**
305     * Distort a list of points in pixels using the OPENCV5/8 models. See image-rotation.md or
306     * https://docs.opencv.org/4.x/d9/d0c/group__calib3d.html for the math here.
307     *
308     * @param pointsList the undistorted points
309     * @param cameraMatrix standard OpenCV camera mat
310     * @param distCoeffs standard OpenCV distortion coefficients. Must OPENCV5 or OPENCV8
311     * @return the list of distorted points
312     */
313    public static List<Point> distortPoints(
314            List<Point> pointsList, Mat cameraMatrix, Mat distCoeffs) {
315        var ret = new ArrayList<Point>();
316
317        var cx = cameraMatrix.get(0, 2)[0];
318        var cy = cameraMatrix.get(1, 2)[0];
319        var fx = cameraMatrix.get(0, 0)[0];
320        var fy = cameraMatrix.get(1, 1)[0];
321
322        var k1 = distCoeffs.get(0, 0)[0];
323        var k2 = distCoeffs.get(0, 1)[0];
324        var p1 = distCoeffs.get(0, 2)[0];
325        var p2 = distCoeffs.get(0, 3)[0];
326        var k3 = distCoeffs.get(0, 4)[0];
327
328        double k4 = 0;
329        double k5 = 0;
330        double k6 = 0;
331        if (distCoeffs.cols() == 8) {
332            k4 = distCoeffs.get(0, 5)[0];
333            k5 = distCoeffs.get(0, 6)[0];
334            k6 = distCoeffs.get(0, 7)[0];
335        }
336
337        for (Point point : pointsList) {
338            // To relative coordinates
339            double xprime = (point.x - cx) / fx; // cx, cy is the center of distortion
340            double yprime = (point.y - cy) / fy;
341
342            double r_sq = xprime * xprime + yprime * yprime; // square of the radius from center
343
344            // Radial distortion
345            double radialDistortion =
346                    (1 + k1 * r_sq + k2 * r_sq * r_sq + k3 * r_sq * r_sq * r_sq)
347                            / (1 + k4 * r_sq + k5 * r_sq * r_sq + k6 * r_sq * r_sq * r_sq);
348            double xDistort = xprime * radialDistortion;
349            double yDistort = yprime * radialDistortion;
350
351            // Tangential distortion
352            xDistort = xDistort + (2 * p1 * xprime * yprime + p2 * (r_sq + 2 * xprime * xprime));
353            yDistort = yDistort + (p1 * (r_sq + 2 * yprime * yprime) + 2 * p2 * xprime * yprime);
354
355            // Back to absolute coordinates.
356            xDistort = xDistort * fx + cx;
357            yDistort = yDistort * fy + cy;
358            ret.add(new Point(xDistort, yDistort));
359        }
360
361        return ret;
362    }
363
364    /**
365     * Project object points from the 3d world into the 2d camera image. The camera
366     * properties(intrinsics, distortion) determine the results of this projection.
367     *
368     * @param cameraMatrix the camera intrinsics matrix in standard OpenCV form
369     * @param distCoeffs the camera distortion matrix in standard OpenCV form
370     * @param camRt The change in basis from world coordinates to camera coordinates. See {@link
371     *     RotTrlTransform3d#makeRelativeTo(Pose3d)}.
372     * @param objectTranslations The 3d points to be projected
373     * @return The 2d points in pixels which correspond to the camera's image of the 3d points
374     */
375    public static Point[] projectPoints(
376            Matrix<N3, N3> cameraMatrix,
377            Matrix<N8, N1> distCoeffs,
378            RotTrlTransform3d camRt,
379            List<Translation3d> objectTranslations) {
380        // translate to OpenCV classes
381        var objectPoints = translationToTvec(objectTranslations.toArray(new Translation3d[0]));
382        // OpenCV rvec/tvec describe a change in basis from world to camera
383        var rvec = rotationToRvec(camRt.getRotation());
384        var tvec = translationToTvec(camRt.getTranslation());
385        var cameraMatrixMat = matrixToMat(cameraMatrix.getStorage());
386        var distCoeffsMat = new MatOfDouble(matrixToMat(distCoeffs.getStorage()));
387        var imagePoints = new MatOfPoint2f();
388        // project to 2d
389        Calib3d.projectPoints(objectPoints, rvec, tvec, cameraMatrixMat, distCoeffsMat, imagePoints);
390        var points = imagePoints.toArray();
391
392        // release our Mats from native memory
393        objectPoints.release();
394        rvec.release();
395        tvec.release();
396        cameraMatrixMat.release();
397        distCoeffsMat.release();
398        imagePoints.release();
399
400        return points;
401    }
402
403    /**
404     * Undistort 2d image points using a given camera's intrinsics and distortion.
405     *
406     * <p>2d image points from {@link #projectPoints(Matrix, Matrix, RotTrlTransform3d, List)
407     * projectPoints()} will naturally be distorted, so this operation is important if the image
408     * points need to be directly used (e.g. 2d yaw/pitch).
409     *
410     * @param cameraMatrix The camera intrinsics matrix in standard OpenCV form
411     * @param distCoeffs The camera distortion matrix in standard OpenCV form
412     * @param points The distorted image points
413     * @return The undistorted image points
414     */
415    public static Point[] undistortPoints(
416            Matrix<N3, N3> cameraMatrix, Matrix<N8, N1> distCoeffs, Point[] points) {
417        var distMat = new MatOfPoint2f(points);
418        var undistMat = new MatOfPoint2f();
419        var cameraMatrixMat = matrixToMat(cameraMatrix.getStorage());
420        var distCoeffsMat = matrixToMat(distCoeffs.getStorage());
421
422        Calib3d.undistortImagePoints(distMat, undistMat, cameraMatrixMat, distCoeffsMat);
423        var undistPoints = undistMat.toArray();
424
425        distMat.release();
426        undistMat.release();
427        cameraMatrixMat.release();
428        distCoeffsMat.release();
429
430        return undistPoints;
431    }
432
433    /**
434     * Gets the (upright) rectangle which bounds this contour.
435     *
436     * <p>Note that rectangle size and position are stored with ints and do not have sub-pixel
437     * accuracy.
438     *
439     * @param points The points to be bounded
440     * @return Rectangle bounding the given points
441     */
442    public static Rect getBoundingRect(Point[] points) {
443        var pointMat = new MatOfPoint2f(points);
444        var rect = Imgproc.boundingRect(pointMat);
445        pointMat.release();
446        return rect;
447    }
448
449    /**
450     * Gets the rotated rectangle with minimum area which bounds this contour.
451     *
452     * <p>Note that rectangle size and position are stored with floats and have sub-pixel accuracy.
453     *
454     * @param points The points to be bounded
455     * @return Rotated rectangle bounding the given points
456     */
457    public static RotatedRect getMinAreaRect(Point[] points) {
458        var pointMat = new MatOfPoint2f(points);
459        var rect = Imgproc.minAreaRect(pointMat);
460        pointMat.release();
461        return rect;
462    }
463
464    /**
465     * Gets the convex hull contour (the outline) of a list of points.
466     *
467     * @param points The input contour
468     * @return The subset of points defining the convex hull. Note that these use ints and not floats.
469     */
470    public static Point[] getConvexHull(Point[] points) {
471        var pointMat = new MatOfPoint(points);
472        // outputHull gives us indices (of corn) that make a convex hull contour
473        var outputHull = new MatOfInt();
474
475        Imgproc.convexHull(pointMat, outputHull);
476
477        int[] indices = outputHull.toArray();
478        outputHull.release();
479        pointMat.release();
480        var convexPoints = new Point[indices.length];
481        for (int i = 0; i < indices.length; i++) {
482            convexPoints[i] = points[indices[i]];
483        }
484        return convexPoints;
485    }
486
487    /**
488     * Finds the transformation(s) that map the camera's pose to the target's pose. The camera's pose
489     * relative to the target is determined by the supplied 3d points of the target's model and their
490     * associated 2d points imaged by the camera. The supplied model translations must be relative to
491     * the target's pose.
492     *
493     * <p>For planar targets, there may be an alternate solution which is plausible given the 2d image
494     * points. This has an associated "ambiguity" which describes the ratio of reprojection error
495     * between the "best" and "alternate" solution.
496     *
497     * <p>This method is intended for use with individual AprilTags, and will not work unless 4 points
498     * are provided.
499     *
500     * @param cameraMatrix The camera intrinsics matrix in standard OpenCV form
501     * @param distCoeffs The camera distortion matrix in standard OpenCV form
502     * @param modelTrls The translations of the object corners. These should have the object pose as
503     *     their origin. These must come in a specific, pose-relative order (in NWU):
504     *     <ul>
505     *       <li>Point 0: [0, -squareLength / 2, squareLength / 2]
506     *       <li>Point 1: [0, squareLength / 2, squareLength / 2]
507     *       <li>Point 2: [0, squareLength / 2, -squareLength / 2]
508     *       <li>Point 3: [0, -squareLength / 2, -squareLength / 2]
509     *     </ul>
510     *
511     * @param imagePoints The projection of these 3d object points into the 2d camera image. The order
512     *     should match the given object point translations.
513     * @return The resulting transformation that maps the camera pose to the target pose and the
514     *     ambiguity if an alternate solution is available.
515     */
516    public static Optional<PnpResult> solvePNP_SQUARE(
517            Matrix<N3, N3> cameraMatrix,
518            Matrix<N8, N1> distCoeffs,
519            List<Translation3d> modelTrls,
520            Point[] imagePoints) {
521        // solvepnp inputs
522        MatOfPoint3f objectMat = new MatOfPoint3f();
523        MatOfPoint2f imageMat = new MatOfPoint2f();
524        MatOfDouble cameraMatrixMat = new MatOfDouble();
525        MatOfDouble distCoeffsMat = new MatOfDouble();
526        var rvecs = new ArrayList<Mat>();
527        var tvecs = new ArrayList<Mat>();
528        Mat rvec = Mat.zeros(3, 1, CvType.CV_32F);
529        Mat tvec = Mat.zeros(3, 1, CvType.CV_32F);
530        Mat reprojectionError = Mat.zeros(2, 1, CvType.CV_32F);
531        try {
532            // IPPE_SQUARE expects our corners in a specific order
533            modelTrls = reorderCircular(modelTrls, true, -1);
534            imagePoints = reorderCircular(Arrays.asList(imagePoints), true, -1).toArray(Point[]::new);
535            // translate to OpenCV classes
536            translationToTvec(modelTrls.toArray(new Translation3d[0])).assignTo(objectMat);
537            imageMat.fromArray(imagePoints);
538            matrixToMat(cameraMatrix.getStorage()).assignTo(cameraMatrixMat);
539            matrixToMat(distCoeffs.getStorage()).assignTo(distCoeffsMat);
540
541            float[] errors = new float[2];
542            Transform3d best = null;
543            Transform3d alt = null;
544
545            for (int tries = 0; tries < 2; tries++) {
546                // calc rvecs/tvecs and associated reprojection error from image points
547                Calib3d.solvePnPGeneric(
548                        objectMat,
549                        imageMat,
550                        cameraMatrixMat,
551                        distCoeffsMat,
552                        rvecs,
553                        tvecs,
554                        false,
555                        Calib3d.SOLVEPNP_IPPE_SQUARE,
556                        rvec,
557                        tvec,
558                        reprojectionError);
559
560                reprojectionError.get(0, 0, errors);
561                // convert to wpilib coordinates
562                best = new Transform3d(tvecToTranslation(tvecs.get(0)), rvecToRotation(rvecs.get(0)));
563
564                if (tvecs.size() > 1) {
565                    alt = new Transform3d(tvecToTranslation(tvecs.get(1)), rvecToRotation(rvecs.get(1)));
566                }
567
568                // check if we got a NaN result
569                if (!Double.isNaN(errors[0])) break;
570                else { // add noise and retry
571                    double[] br = imageMat.get(0, 0);
572                    br[0] -= 0.001;
573                    br[1] -= 0.001;
574                    imageMat.put(0, 0, br);
575                }
576            }
577
578            // check if solvePnP failed with NaN results and retrying failed
579            if (Double.isNaN(errors[0])) throw new Exception("SolvePNP_SQUARE NaN result");
580
581            if (alt != null)
582                return Optional.of(new PnpResult(best, alt, errors[0] / errors[1], errors[0], errors[1]));
583            else return Optional.empty();
584        }
585        // solvePnP failed
586        catch (Exception e) {
587            System.err.println("SolvePNP_SQUARE failed!");
588            e.printStackTrace();
589            return Optional.empty();
590        } finally {
591            // release our Mats from native memory
592            objectMat.release();
593            imageMat.release();
594            cameraMatrixMat.release();
595            distCoeffsMat.release();
596            for (var v : rvecs) v.release();
597            for (var v : tvecs) v.release();
598            rvec.release();
599            tvec.release();
600            reprojectionError.release();
601        }
602    }
603
604    /**
605     * Finds the transformation that maps the camera's pose to the origin of the supplied object. An
606     * "object" is simply a set of known 3d translations that correspond to the given 2d points. If,
607     * for example, the object translations are given relative to close-right corner of the blue
608     * alliance(the default origin), a camera-to-origin transformation is returned. If the
609     * translations are relative to a target's pose, a camera-to-target transformation is returned.
610     *
611     * <p>There must be at least 3 points to use this method. This does not return an alternate
612     * solution-- if you are intending to use solvePNP on a single AprilTag, see {@link
613     * #solvePNP_SQUARE} instead.
614     *
615     * @param cameraMatrix The camera intrinsics matrix in standard OpenCV form
616     * @param distCoeffs The camera distortion matrix in standard OpenCV form
617     * @param objectTrls The translations of the object corners, relative to the field.
618     * @param imagePoints The projection of these 3d object points into the 2d camera image. The order
619     *     should match the given object point translations.
620     * @return The resulting transformation that maps the camera pose to the target pose. If the 3d
621     *     model points are supplied relative to the origin, this transformation brings the camera to
622     *     the origin.
623     */
624    public static Optional<PnpResult> solvePNP_SQPNP(
625            Matrix<N3, N3> cameraMatrix,
626            Matrix<N8, N1> distCoeffs,
627            List<Translation3d> objectTrls,
628            Point[] imagePoints) {
629        try {
630            // translate to OpenCV classes
631            MatOfPoint3f objectMat = translationToTvec(objectTrls.toArray(new Translation3d[0]));
632            MatOfPoint2f imageMat = new MatOfPoint2f(imagePoints);
633            Mat cameraMatrixMat = matrixToMat(cameraMatrix.getStorage());
634            Mat distCoeffsMat = matrixToMat(distCoeffs.getStorage());
635            var rvecs = new ArrayList<Mat>();
636            var tvecs = new ArrayList<Mat>();
637            Mat rvec = Mat.zeros(3, 1, CvType.CV_32F);
638            Mat tvec = Mat.zeros(3, 1, CvType.CV_32F);
639            Mat reprojectionError = new Mat();
640            // calc rvec/tvec from image points
641            Calib3d.solvePnPGeneric(
642                    objectMat,
643                    imageMat,
644                    cameraMatrixMat,
645                    distCoeffsMat,
646                    rvecs,
647                    tvecs,
648                    false,
649                    Calib3d.SOLVEPNP_SQPNP,
650                    rvec,
651                    tvec,
652                    reprojectionError);
653
654            float[] error = new float[1];
655            reprojectionError.get(0, 0, error);
656            // convert to wpilib coordinates
657            var best = new Transform3d(tvecToTranslation(tvecs.get(0)), rvecToRotation(rvecs.get(0)));
658
659            // release our Mats from native memory
660            objectMat.release();
661            imageMat.release();
662            cameraMatrixMat.release();
663            distCoeffsMat.release();
664            for (var v : rvecs) v.release();
665            for (var v : tvecs) v.release();
666            rvec.release();
667            tvec.release();
668            reprojectionError.release();
669
670            // check if solvePnP failed with NaN results
671            if (Double.isNaN(error[0])) throw new Exception("SolvePNP_SQPNP NaN result");
672
673            return Optional.of(new PnpResult(best, error[0]));
674        } catch (Exception e) {
675            System.err.println("SolvePNP_SQPNP failed!");
676            e.printStackTrace();
677            return Optional.empty();
678        }
679    }
680}