Change SimCameraProperties to enable chaining of setters (#1731)

This commit is contained in:
Anon Ymous
2025-01-28 13:03:03 -05:00
committed by GitHub
parent 78b82e3a96
commit a5d007e258

View File

@@ -160,11 +160,12 @@ public class SimCameraProperties {
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 class SimCameraProperties {
// 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<N3, N3> camIntrinsics, Matrix<N8, N1> distCoeffs) {
this.resWidth = resWidth;
this.resHeight = resHeight;
@@ -222,43 +225,54 @@ public class SimCameraProperties {
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. <b>Exposure time limits
* FPS if set!</b>
*/
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. <b>Frame speed(from FPS) is limited to this!</b>
*/
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() {