Skip to content

Commit a5d007e

Browse files
Change SimCameraProperties to enable chaining of setters (#1731)
1 parent 78b82e3 commit a5d007e

File tree

1 file changed

+22
-8
lines changed

1 file changed

+22
-8
lines changed

photon-lib/src/main/java/org/photonvision/simulation/SimCameraProperties.java

Lines changed: 22 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -160,11 +160,12 @@ public SimCameraProperties(Path path, int width, int height) throws IOException
160160
if (!success) throw new IOException("Requested resolution not found in calibration");
161161
}
162162

163-
public void setRandomSeed(long seed) {
163+
public SimCameraProperties setRandomSeed(long seed) {
164164
rand.setSeed(seed);
165+
return this;
165166
}
166167

167-
public void setCalibration(int resWidth, int resHeight, Rotation2d fovDiag) {
168+
public SimCameraProperties setCalibration(int resWidth, int resHeight, Rotation2d fovDiag) {
168169
if (fovDiag.getDegrees() < 1 || fovDiag.getDegrees() > 179) {
169170
fovDiag = Rotation2d.fromDegrees(MathUtil.clamp(fovDiag.getDegrees(), 1, 179));
170171
DriverStation.reportError(
@@ -189,9 +190,11 @@ public void setCalibration(int resWidth, int resHeight, Rotation2d fovDiag) {
189190
// create camera intrinsics matrix
190191
var camIntrinsics = MatBuilder.fill(Nat.N3(), Nat.N3(), fx, 0, cx, 0, fy, cy, 0, 0, 1);
191192
setCalibration(resWidth, resHeight, camIntrinsics, distCoeff);
193+
194+
return this;
192195
}
193196

194-
public void setCalibration(
197+
public SimCameraProperties setCalibration(
195198
int resWidth, int resHeight, Matrix<N3, N3> camIntrinsics, Matrix<N8, N1> distCoeffs) {
196199
this.resWidth = resWidth;
197200
this.resHeight = resHeight;
@@ -222,43 +225,54 @@ public void setCalibration(
222225
viewplanes.add(
223226
new DMatrix3(translation3d.getX(), translation3d.getY(), translation3d.getZ()));
224227
}
228+
229+
return this;
225230
}
226231

227-
public void setCalibError(double avgErrorPx, double errorStdDevPx) {
232+
public SimCameraProperties setCalibError(double avgErrorPx, double errorStdDevPx) {
228233
this.avgErrorPx = avgErrorPx;
229234
this.errorStdDevPx = errorStdDevPx;
235+
return this;
230236
}
231237

232238
/**
233239
* @param fps The average frames per second the camera should process at. <b>Exposure time limits
234240
* FPS if set!</b>
235241
*/
236-
public void setFPS(double fps) {
242+
public SimCameraProperties setFPS(double fps) {
237243
frameSpeedMs = Math.max(1000.0 / fps, exposureTimeMs);
244+
245+
return this;
238246
}
239247

240248
/**
241249
* @param exposureTimeMs The amount of time the "shutter" is open for one frame. Affects motion
242250
* blur. <b>Frame speed(from FPS) is limited to this!</b>
243251
*/
244-
public void setExposureTimeMs(double exposureTimeMs) {
252+
public SimCameraProperties setExposureTimeMs(double exposureTimeMs) {
245253
this.exposureTimeMs = exposureTimeMs;
246254
frameSpeedMs = Math.max(frameSpeedMs, exposureTimeMs);
255+
256+
return this;
247257
}
248258

249259
/**
250260
* @param avgLatencyMs The average latency (from image capture to data published) in milliseconds
251261
* a frame should have
252262
*/
253-
public void setAvgLatencyMs(double avgLatencyMs) {
263+
public SimCameraProperties setAvgLatencyMs(double avgLatencyMs) {
254264
this.avgLatencyMs = avgLatencyMs;
265+
266+
return this;
255267
}
256268

257269
/**
258270
* @param latencyStdDevMs The standard deviation in milliseconds of the latency
259271
*/
260-
public void setLatencyStdDevMs(double latencyStdDevMs) {
272+
public SimCameraProperties setLatencyStdDevMs(double latencyStdDevMs) {
261273
this.latencyStdDevMs = latencyStdDevMs;
274+
275+
return this;
262276
}
263277

264278
public int getResWidth() {

0 commit comments

Comments
 (0)