From 9c2068ae46295be0b785b17a2446d411387d9cdc Mon Sep 17 00:00:00 2001 From: Anon Ymous <73802848+ancientstraits@users.noreply.github.com> Date: Wed, 15 Jan 2025 10:15:39 -0500 Subject: [PATCH] Update SimCameraProperties.java --- .../simulation/SimCameraProperties.java | 30 ++++++++++++++----- 1 file changed, 22 insertions(+), 8 deletions(-) diff --git a/photon-lib/src/main/java/org/photonvision/simulation/SimCameraProperties.java b/photon-lib/src/main/java/org/photonvision/simulation/SimCameraProperties.java index 1e069ac06c..f9b7f8a462 100644 --- a/photon-lib/src/main/java/org/photonvision/simulation/SimCameraProperties.java +++ b/photon-lib/src/main/java/org/photonvision/simulation/SimCameraProperties.java @@ -160,11 +160,12 @@ public SimCameraProperties(Path path, int width, int height) throws IOException if (!success) throw new IOException("Requested resolution not found in calibration"); } - public void setRandomSeed(long seed) { + public SimCameraProperties setRandomSeed(long seed) { rand.setSeed(seed); + return this; } - public void setCalibration(int resWidth, int resHeight, Rotation2d fovDiag) { + public SimCameraProperties setCalibration(int resWidth, int resHeight, Rotation2d fovDiag) { if (fovDiag.getDegrees() < 1 || fovDiag.getDegrees() > 179) { fovDiag = Rotation2d.fromDegrees(MathUtil.clamp(fovDiag.getDegrees(), 1, 179)); DriverStation.reportError( @@ -189,9 +190,11 @@ public void setCalibration(int resWidth, int resHeight, Rotation2d fovDiag) { // create camera intrinsics matrix var camIntrinsics = MatBuilder.fill(Nat.N3(), Nat.N3(), fx, 0, cx, 0, fy, cy, 0, 0, 1); setCalibration(resWidth, resHeight, camIntrinsics, distCoeff); + + return this; } - public void setCalibration( + public SimCameraProperties setCalibration( int resWidth, int resHeight, Matrix camIntrinsics, Matrix distCoeffs) { this.resWidth = resWidth; this.resHeight = resHeight; @@ -222,43 +225,54 @@ public void setCalibration( viewplanes.add( new DMatrix3(translation3d.getX(), translation3d.getY(), translation3d.getZ())); } + + return this; } - public void setCalibError(double avgErrorPx, double errorStdDevPx) { + public SimCameraProperties setCalibError(double avgErrorPx, double errorStdDevPx) { this.avgErrorPx = avgErrorPx; this.errorStdDevPx = errorStdDevPx; + return this; } /** * @param fps The average frames per second the camera should process at. Exposure time limits * FPS if set! */ - public void setFPS(double fps) { + public SimCameraProperties setFPS(double fps) { frameSpeedMs = Math.max(1000.0 / fps, exposureTimeMs); + + return this; } /** * @param exposureTimeMs The amount of time the "shutter" is open for one frame. Affects motion * blur. Frame speed(from FPS) is limited to this! */ - public void setExposureTimeMs(double exposureTimeMs) { + public SimCameraProperties setExposureTimeMs(double exposureTimeMs) { this.exposureTimeMs = exposureTimeMs; frameSpeedMs = Math.max(frameSpeedMs, exposureTimeMs); + + return this; } /** * @param avgLatencyMs The average latency (from image capture to data published) in milliseconds * a frame should have */ - public void setAvgLatencyMs(double avgLatencyMs) { + public SimCameraProperties setAvgLatencyMs(double avgLatencyMs) { this.avgLatencyMs = avgLatencyMs; + + return this; } /** * @param latencyStdDevMs The standard deviation in milliseconds of the latency */ - public void setLatencyStdDevMs(double latencyStdDevMs) { + public SimCameraProperties setLatencyStdDevMs(double latencyStdDevMs) { this.latencyStdDevMs = latencyStdDevMs; + + return this; } public int getResWidth() {