diff --git a/J_observations.spy b/J_observations.spy new file mode 100644 index 0000000000..217a11aa09 Binary files /dev/null and b/J_observations.spy differ diff --git a/JtJ.spy b/JtJ.spy new file mode 100644 index 0000000000..5818cdcc6c Binary files /dev/null and b/JtJ.spy differ diff --git a/build.gradle b/build.gradle index d0be427460..cd13e8d279 100644 --- a/build.gradle +++ b/build.gradle @@ -41,7 +41,7 @@ ext { rknnVersion = "v2026.0.1" rubikVersion = "v2026.0.1" frcYear = "2026" - mrcalVersion = "v2026.0.0"; + mrcalVersion = "dev-v2026.0.0-19-g646eb18"; pubVersion = versionString isDev = pubVersion.startsWith("dev") diff --git a/gradient_0.spy b/gradient_0.spy new file mode 100644 index 0000000000..49aac2aef0 Binary files /dev/null and b/gradient_0.spy differ diff --git a/gradient_1.spy b/gradient_1.spy new file mode 100644 index 0000000000..27a308930e Binary files /dev/null and b/gradient_1.spy differ diff --git a/gradient_2.spy b/gradient_2.spy new file mode 100644 index 0000000000..c5d9eb7ad2 Binary files /dev/null and b/gradient_2.spy differ diff --git a/gradient_3.spy b/gradient_3.spy new file mode 100644 index 0000000000..192054af8c Binary files /dev/null and b/gradient_3.spy differ diff --git a/gradient_4.spy b/gradient_4.spy new file mode 100644 index 0000000000..1f53deab42 Binary files /dev/null and b/gradient_4.spy differ diff --git a/heatmap.svg b/heatmap.svg new file mode 100644 index 0000000000..da8e50ca01 --- /dev/null +++ b/heatmap.svg @@ -0,0 +1,5686 @@ + + + + + + + + 2026-01-31T10:15:21.934047 + image/svg+xml + + + Matplotlib v3.6.3, https://matplotlib.org/ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/photon-client/src/components/app/photon-uncertainty-visualizer.vue b/photon-client/src/components/app/photon-uncertainty-visualizer.vue new file mode 100644 index 0000000000..b348afa544 --- /dev/null +++ b/photon-client/src/components/app/photon-uncertainty-visualizer.vue @@ -0,0 +1,254 @@ + + + diff --git a/photon-client/src/components/cameras/CameraCalibrationInfoCard.vue b/photon-client/src/components/cameras/CameraCalibrationInfoCard.vue index 7608d320cd..f09141baf6 100644 --- a/photon-client/src/components/cameras/CameraCalibrationInfoCard.vue +++ b/photon-client/src/components/cameras/CameraCalibrationInfoCard.vue @@ -7,6 +7,7 @@ import { computed, inject, ref } from "vue"; import { axiosPost, getResolutionString, parseJsonFile } from "@/lib/PhotonUtils"; import { useTheme } from "vuetify"; import PvDeleteModal from "@/components/common/pv-delete-modal.vue"; +import PhotonUncertaintyVisualizer from "@/components/app/photon-uncertainty-visualizer.vue"; const theme = useTheme(); const props = defineProps<{ @@ -161,6 +162,7 @@ const viewingImg = ref(0); Details Observations + Uncertainty @@ -308,6 +310,19 @@ const viewingImg = ref(0); + +

+ Calibration unceratinty, in pixels, looking out to infinity. Lower numbers are better. +

+

Uncertainty measures how sure we are about the pixel location that a ray entering our camera would fall onto. Lower numbers imply higher certainty. To decrease uncertainty, capture more varied pictures across the full field of view of your camera. +

+

+ A lower unceratinty doesn't necesarrily mean that the calibration is more accurate -- just that our solver had more information that seemed to correspond. Confounding factors (like incorrect square size) can still lead to inaccurate results. +

+

+ For more information, review Mrcal's uncertainty documentation +

+
@@ -328,8 +343,17 @@ const viewingImg = ref(0); :resolution="props.videoFormat.resolution" title="Camera to Board Transforms" /> - + + + + +
observation image
diff --git a/photon-core/src/main/java/org/photonvision/vision/calibration/CameraCalibrationCoefficients.java b/photon-core/src/main/java/org/photonvision/vision/calibration/CameraCalibrationCoefficients.java index ad0f9db98b..dabaa34845 100644 --- a/photon-core/src/main/java/org/photonvision/vision/calibration/CameraCalibrationCoefficients.java +++ b/photon-core/src/main/java/org/photonvision/vision/calibration/CameraCalibrationCoefficients.java @@ -22,16 +22,24 @@ import com.fasterxml.jackson.annotation.JsonIgnore; import com.fasterxml.jackson.annotation.JsonIgnoreProperties; import com.fasterxml.jackson.annotation.JsonProperty; +import java.util.ArrayList; import java.util.Arrays; import java.util.List; import org.opencv.core.Mat; import org.opencv.core.MatOfDouble; +import org.opencv.core.Point3; import org.opencv.core.Size; +import org.photonvision.common.logging.LogGroup; +import org.photonvision.common.logging.Logger; +import org.photonvision.mrcal.MrCalJNI; import org.photonvision.vision.opencv.ImageRotationMode; import org.photonvision.vision.opencv.Releasable; @JsonIgnoreProperties(ignoreUnknown = true) public class CameraCalibrationCoefficients implements Releasable { + private static final Logger logger = + new Logger(CameraCalibrationCoefficients.class, LogGroup.Data); + @JsonProperty("resolution") public final Size unrotatedImageSize; @@ -253,4 +261,102 @@ public UICameraCalibrationCoefficients cloneWithoutObservations() { calobjectSpacing, lensmodel); } + + @JsonIgnore + public double[] framePosesToRtToref() { + double[] ret = new double[observations.size() * 6]; + + for (int i = 0; i < observations.size(); i++) { + var o = observations.get(i); + var pose = o.optimisedCameraToObject; + var r = pose.getRotation().toVector(); + var t = pose.getTranslation().toVector(); + ret[i * 6 + 0] = r.get(0); + ret[i * 6 + 1] = r.get(1); + ret[i * 6 + 2] = r.get(2); + ret[i * 6 + 3] = t.get(0); + ret[i * 6 + 4] = t.get(1); + ret[i * 6 + 5] = t.get(2); + } + + return ret; + } + + /** + * Estimate uncertainty across a grid of points. Returned list is (u, v, uncertainty) in pixels. + * Please find a better home for this code + */ + @JsonIgnore + public List estimateUncertainty() { + // number of intersections + int boardWidth = (int) calobjectSize.width; + int boardHeight = (int) calobjectSize.height; + + double[] xylevels = new double[boardWidth * boardHeight * 3 * observations.size()]; + var rt_ref_frames = framePosesToRtToref(); + + int xylevelsIdx = 0; + for (var board : observations) { + if (board.locationInImageSpace.size() != board.cornersUsed.length) { + logger.error("Length mismatch", new RuntimeException()); + } + + var corners = board.locationInImageSpace; + + // xylevels is row-major per chessboard + for (int boardCornerIdx = 0; boardCornerIdx < corners.size(); boardCornerIdx++) { + var corner = corners.get(boardCornerIdx); + double level = board.cornersUsed[boardCornerIdx] ? 1.0 : -1.0; + + xylevels[xylevelsIdx * 3 + 0] = corner.x; + xylevels[xylevelsIdx * 3 + 1] = corner.y; + xylevels[xylevelsIdx * 3 + 2] = level; + + xylevelsIdx += 1; + } + } + + double warpX, warpY; + if (calobjectWarp == null || calobjectWarp.length != 2) { + warpX = 0; + warpY = 0; + } else { + warpX = calobjectWarp[0]; + warpY = calobjectWarp[1]; + } + + var mrcalIntrinsics = new double[12]; + Arrays.fill(mrcalIntrinsics, 0); + // core is fx fy cx cy + var core = this.cameraIntrinsics.getAsWpilibMat(); + mrcalIntrinsics[0] = core.get(0, 0); + mrcalIntrinsics[1] = core.get(1, 1); + mrcalIntrinsics[2] = core.get(0, 2); + mrcalIntrinsics[3] = core.get(1, 2); + // distortion + System.arraycopy( + this.getDistCoeffsArr(), 0, mrcalIntrinsics, 4, this.getDistCoeffsArr().length); + + var uncertainty = // x, y, uncertainty + MrCalJNI.compute_uncertainty( + xylevels, + mrcalIntrinsics, + rt_ref_frames, + boardWidth, + boardHeight, + calobjectSpacing, + (int) unrotatedImageSize.width, + (int) unrotatedImageSize.height, + 60, + 40, + warpX, + warpY); + + var ret = new ArrayList(); + for (int j = 0; j < uncertainty.length; j += 3) { + ret.add(new Point3(uncertainty[j + 0], uncertainty[j + 1], uncertainty[j + 2])); + } + + return ret; + } } diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/FileVisionSource.java b/photon-core/src/main/java/org/photonvision/vision/camera/FileVisionSource.java index 76737fbf20..4c7d368bcd 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/FileVisionSource.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/FileVisionSource.java @@ -113,6 +113,7 @@ public static class FileSourceSettables extends VisionSourceSettables { frameStaticProperties.imageHeight, 30); videoModes.put(0, videoMode); + videoModes.put(1, new VideoMode(PixelFormat.kMJPEG, 1280, 720, 30)); } @Override diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/Calibrate3dPipeTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/Calibrate3dPipeTest.java index ccb5e0c027..654f237605 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/Calibrate3dPipeTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/Calibrate3dPipeTest.java @@ -25,6 +25,7 @@ import java.io.IOException; import java.nio.file.Path; import org.junit.jupiter.api.BeforeAll; +import org.junit.jupiter.api.Test; import org.junitpioneer.jupiter.cartesian.CartesianTest; import org.junitpioneer.jupiter.cartesian.CartesianTest.Enum; import org.junitpioneer.jupiter.cartesian.CartesianTest.Values; @@ -117,6 +118,17 @@ private CalibrationDatasets( } } + @Test + public void testFoo() { + calibrateCommon( + new Size(1280, 720), + Path.of("/mnt/c/Users/matth/Documents/camera-cal-images/lifecam_squares_1280x720").toFile(), + new Size(11, 11), + BoardType.CHESSBOARD, + true, + false); + } + /** * Run camera calibration on a given dataset * @@ -229,7 +241,7 @@ public static void calibrateCommon( calibration3dPipeline.getSettings().useOldPattern = useOldPattern; for (var file : directoryListing) { - if (file.isFile()) { + if (file.isFile() && file.getName().endsWith("png")) { calibration3dPipeline.takeSnapshot(); var frame = new Frame( diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/UncertaintyTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/UncertaintyTest.java new file mode 100644 index 0000000000..598de7b25b --- /dev/null +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/UncertaintyTest.java @@ -0,0 +1,70 @@ +/* + * Copyright (C) Photon Vision. + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ + +package org.photonvision.vision.pipeline; + +import com.fasterxml.jackson.databind.ObjectMapper; +import java.io.FileWriter; +import java.io.IOException; +import java.nio.file.Path; +import org.junit.jupiter.api.BeforeAll; +import org.junit.jupiter.api.Test; +import org.opencv.core.Point3; +import org.photonvision.common.LoadJNI; +import org.photonvision.common.logging.LogGroup; +import org.photonvision.common.logging.LogLevel; +import org.photonvision.common.logging.Logger; +import org.photonvision.vision.calibration.CameraCalibrationCoefficients; + +public class UncertaintyTest { + @BeforeAll + public static void init() throws IOException { + LoadJNI.loadLibraries(); + LoadJNI.forceLoad(LoadJNI.JNITypes.MRCAL); + + var logLevel = LogLevel.DEBUG; + Logger.setLevel(LogGroup.Camera, logLevel); + Logger.setLevel(LogGroup.WebServer, logLevel); + Logger.setLevel(LogGroup.VisionModule, logLevel); + Logger.setLevel(LogGroup.Data, logLevel); + Logger.setLevel(LogGroup.Config, logLevel); + Logger.setLevel(LogGroup.General, logLevel); + } + + @Test + public void testGenerateUncertainty() throws IOException { + long pid = ProcessHandle.current().pid(); + System.out.println("Current Process ID (PID): " + pid); + + var cameraCal = + new ObjectMapper() + .readValue( + Path.of( + "/mnt/c/Users/matth/Downloads/photon_calibration_4c910967-fda0-4936-96af-ec4a9c969318_1280x720.json") + .toFile(), + CameraCalibrationCoefficients.class); + + var uncertainty = cameraCal.estimateUncertainty().toArray(new Point3[0]); + + try (FileWriter f = new FileWriter("out")) { + for (int i = 0; i < uncertainty.length; i++) { + var p = uncertainty[i]; + f.write(p.x + "," + p.y + "," + p.z + "\n"); + } + } + } +} diff --git a/photon-server/src/main/java/org/photonvision/Main.java b/photon-server/src/main/java/org/photonvision/Main.java index b07538a587..67178a99ee 100644 --- a/photon-server/src/main/java/org/photonvision/Main.java +++ b/photon-server/src/main/java/org/photonvision/Main.java @@ -17,6 +17,7 @@ package org.photonvision; +import com.fasterxml.jackson.databind.ObjectMapper; import edu.wpi.first.hal.HAL; import edu.wpi.first.math.geometry.Rotation2d; import java.io.IOException; @@ -188,6 +189,18 @@ private static void addTestModeSources() { 1, CameraLensModel.LENSMODEL_OPENCV)); + try { + camConf2026.calibrations.add( + new ObjectMapper() + .readValue( + Path.of( + "/mnt/c/Users/matth/Downloads/photon_calibration_4c910967-fda0-4936-96af-ec4a9c969318_1280x720.json") + .toFile(), + CameraCalibrationCoefficients.class)); + } catch (Exception e) { + e.printStackTrace(); + } + logger.info("Added test camera calibration for WPI2026 " + camConf2026.calibrations); var pipeline2026 = new AprilTagPipelineSettings(); diff --git a/photon-server/src/main/java/org/photonvision/server/RequestHandler.java b/photon-server/src/main/java/org/photonvision/server/RequestHandler.java index 63ffd2ec3d..cfb017ec4c 100644 --- a/photon-server/src/main/java/org/photonvision/server/RequestHandler.java +++ b/photon-server/src/main/java/org/photonvision/server/RequestHandler.java @@ -1052,6 +1052,35 @@ public static void onCalibrationJsonRequest(Context ctx) { ctx.status(200); } + public static void onUncertaintyJsonRequest(Context ctx) { + String cameraUniqueName = ctx.queryParam("cameraUniqueName"); + var width = Integer.parseInt(ctx.queryParam("width")); + var height = Integer.parseInt(ctx.queryParam("height")); + + var module = VisionSourceManager.getInstance().vmm.getModule(cameraUniqueName); + if (module == null) { + ctx.status(404); + return; + } + + CameraCalibrationCoefficients calList = + module.getStateAsCameraConfig().calibrations.stream() + .filter( + it -> + Math.abs(it.unrotatedImageSize.width - width) < 1e-4 + && Math.abs(it.unrotatedImageSize.height - height) < 1e-4) + .findFirst() + .orElse(null); + + if (calList == null) { + ctx.status(404); + return; + } + + ctx.json(calList.estimateUncertainty()); + ctx.status(200); + } + private record CalibrationRemoveRequest(int width, int height, String cameraUniqueName) {} public static void onCalibrationRemoveRequest(Context ctx) { diff --git a/photon-server/src/main/java/org/photonvision/server/Server.java b/photon-server/src/main/java/org/photonvision/server/Server.java index 573592a183..7ee8cdb813 100644 --- a/photon-server/src/main/java/org/photonvision/server/Server.java +++ b/photon-server/src/main/java/org/photonvision/server/Server.java @@ -131,6 +131,7 @@ private static void start(int port) { app.post("/api/settings/camera/setNickname", RequestHandler::onCameraNicknameChangeRequest); app.get("/api/settings/camera/getCalibImages", RequestHandler::onCameraCalibImagesRequest); app.get("/api/settings/camera/getCalibration", RequestHandler::onCalibrationJsonRequest); + app.get("/api/settings/camera/getUncertainty", RequestHandler::onUncertaintyJsonRequest); // Utilities app.post("/api/utils/offlineUpdate", RequestHandler::onOfflineUpdateRequest);