From da4893048c01068c42dc23df667d0bebb1fab97f Mon Sep 17 00:00:00 2001 From: Matt Date: Sat, 30 Dec 2023 21:48:52 -0800 Subject: [PATCH] Swap to PNG and serialize insolution --- photon-client/src/types/SettingTypes.ts | 1 + .../photonvision/vision/calibration/BoardObservation.java | 7 ++++++- .../org/photonvision/vision/pipe/impl/Calibrate3dPipe.java | 2 +- .../photonvision/vision/pipeline/Calibrate3dPipeline.java | 2 +- .../main/java/org/photonvision/server/RequestHandler.java | 2 +- 5 files changed, 10 insertions(+), 4 deletions(-) diff --git a/photon-client/src/types/SettingTypes.ts b/photon-client/src/types/SettingTypes.ts index da035cafeb..cc134268ce 100644 --- a/photon-client/src/types/SettingTypes.ts +++ b/photon-client/src/types/SettingTypes.ts @@ -113,6 +113,7 @@ export interface BoardObservation { locationInImageSpace: CvPoint[]; reprojectionErrors: CvPoint[]; optimisedCameraToObject: Pose3d; + includeObservationInCalibration: boolean; } export interface CameraCalibrationResult { diff --git a/photon-core/src/main/java/org/photonvision/vision/calibration/BoardObservation.java b/photon-core/src/main/java/org/photonvision/vision/calibration/BoardObservation.java index a052016151..3c31cebd19 100644 --- a/photon-core/src/main/java/org/photonvision/vision/calibration/BoardObservation.java +++ b/photon-core/src/main/java/org/photonvision/vision/calibration/BoardObservation.java @@ -40,15 +40,20 @@ public final class BoardObservation { // Solver optimized board poses public Pose3d optimisedCameraToObject; + // If we should use this observation when re-calculating camera calibration + public boolean includeObservationInCalibration; + @JsonCreator public BoardObservation( @JsonProperty("locationInObjectSpace") List locationInObjectSpace, @JsonProperty("locationInImageSpace") List locationInImageSpace, @JsonProperty("reprojectionErrors") List reprojectionErrors, - @JsonProperty("optimisedCameraToObject") Pose3d optimisedCameraToObject) { + @JsonProperty("optimisedCameraToObject") Pose3d optimisedCameraToObject, + @JsonProperty("includeObservationInCalibration") boolean includeObservationInCalibration) { this.locationInObjectSpace = locationInObjectSpace; this.locationInImageSpace = locationInImageSpace; this.reprojectionErrors = reprojectionErrors; this.optimisedCameraToObject = optimisedCameraToObject; + this.includeObservationInCalibration = includeObservationInCalibration; } } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Calibrate3dPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Calibrate3dPipe.java index 398e5f9608..1f82085758 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Calibrate3dPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Calibrate3dPipe.java @@ -152,7 +152,7 @@ protected CameraCalibrationCoefficients process(List> in) var camToBoard = MathUtils.opencvRTtoPose3d(rvecs.get(i), tvecs.get(i)); - observations.add(new BoardObservation(i_objPts, i_imgPts, reprojectionError, camToBoard)); + observations.add(new BoardObservation(i_objPts, i_imgPts, reprojectionError, camToBoard, true)); } jac_temp.release(); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/Calibrate3dPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/Calibrate3dPipeline.java index b11afaef41..4f3caef569 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/Calibrate3dPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/Calibrate3dPipeline.java @@ -161,7 +161,7 @@ private void saveCalImage(Mat img) { logger.error("Could not create save folder! " + folder); } Imgcodecs.imwrite( - Path.of(folder.toAbsolutePath().toString(), "img" + foundCornersList.size() + ".jpg") + Path.of(folder.toAbsolutePath().toString(), "img" + foundCornersList.size() + ".png") .toString(), img); } 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 283429e971..d93fd58f34 100644 --- a/photon-server/src/main/java/org/photonvision/server/RequestHandler.java +++ b/photon-server/src/main/java/org/photonvision/server/RequestHandler.java @@ -615,7 +615,7 @@ public static void onCameraCalibImagesRequest(Context ctx) { var bufferedImage = ImageIO.read(calibImg); var buffer = new ByteArrayOutputStream(); - ImageIO.write(bufferedImage, "jpg", buffer); + ImageIO.write(bufferedImage, "png", buffer); byte[] data = buffer.toByteArray(); snapshotData.put("snapshotData", data);