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