Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Calculate average reprojection error when loading SimCameraProperties #1673

Open
wants to merge 4 commits into
base: main
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,6 @@ public class SimCameraProperties {
private int resHeight;
private Matrix<N3, N3> camIntrinsics;
private Matrix<N8, N1> distCoeffs;
private double avgErrorPx;
private double errorStdDevPx;
// performance
private double frameSpeedMs = 0;
Expand All @@ -92,72 +91,36 @@ public SimCameraProperties() {
* Reads camera properties from a photonvision <code>config.json</code> file. This is only the
* resolution, camera intrinsics, distortion coefficients, and average/std. dev. pixel error.
* Other camera properties must be set.
*
* @deprecated Support for loading camera calibration has been deprecated. Please use a prebuilt camera config or the default constructor.
*
* @param path Path to the <code>config.json</code> file
* @param width The width of the desired resolution in the JSON
* @param height The height of the desired resolution in the JSON
* @throws IOException If reading the JSON fails, either from an invalid path or a missing/invalid
* calibrated resolution.
*/
@Deprecated
public SimCameraProperties(String path, int width, int height) throws IOException {
this(Path.of(path), width, height);
this();
}

/**
* Reads camera properties from a photonvision <code>config.json</code> file. This is only the
* resolution, camera intrinsics, distortion coefficients, and average/std. dev. pixel error.
* Other camera properties must be set.
*
* @deprecated Support for loading camera calibration has been deprecated. Please use a prebuilt camera config or the default constructor.
*
* @param path Path to the <code>config.json</code> file
* @param width The width of the desired resolution in the JSON
* @param height The height of the desired resolution in the JSON
* @throws IOException If reading the JSON fails, either from an invalid path or a missing/invalid
* calibrated resolution.
*/
@Deprecated
public SimCameraProperties(Path path, int width, int height) throws IOException {
var mapper = new ObjectMapper();
var json = mapper.readTree(path.toFile());
json = json.get("calibrations");
boolean success = false;
try {
for (int i = 0; i < json.size() && !success; i++) {
// check if this calibration entry is our desired resolution
var calib = json.get(i);
int jsonWidth = calib.get("resolution").get("width").asInt();
int jsonHeight = calib.get("resolution").get("height").asInt();
if (jsonWidth != width || jsonHeight != height) continue;
// get the relevant calibration values
var jsonIntrinsicsNode = calib.get("cameraIntrinsics").get("data");
double[] jsonIntrinsics = new double[jsonIntrinsicsNode.size()];
for (int j = 0; j < jsonIntrinsicsNode.size(); j++) {
jsonIntrinsics[j] = jsonIntrinsicsNode.get(j).asDouble();
}
var jsonDistortNode = calib.get("distCoeffs").get("data");
double[] jsonDistortion = new double[8];
Arrays.fill(jsonDistortion, 0);
for (int j = 0; j < jsonDistortNode.size(); j++) {
jsonDistortion[j] = jsonDistortNode.get(j).asDouble();
}
var jsonViewErrors = calib.get("perViewErrors");
double jsonAvgError = 0;
for (int j = 0; j < jsonViewErrors.size(); j++) {
jsonAvgError += jsonViewErrors.get(j).asDouble();
}
jsonAvgError /= jsonViewErrors.size();
double jsonErrorStdDev = calib.get("standardDeviation").asDouble();
// assign the read JSON values to this CameraProperties
setCalibration(
jsonWidth,
jsonHeight,
MatBuilder.fill(Nat.N3(), Nat.N3(), jsonIntrinsics),
MatBuilder.fill(Nat.N8(), Nat.N1(), jsonDistortion));
setCalibError(jsonAvgError, jsonErrorStdDev);
success = true;
}
} catch (Exception e) {
throw new IOException("Invalid calibration JSON");
}
if (!success) throw new IOException("Requested resolution not found in calibration");
this();
}

public void setRandomSeed(long seed) {
Expand Down Expand Up @@ -224,8 +187,25 @@ public void setCalibration(
}
}

/**
* Assigns calibration error properties of the simulated camera.
*
* @deprecated avgErrorPx is unused and can be removed from the argument list.
*
* @param avgErrorPx Average pixel error
* @param errorStdDevPx Pixel error standard deviation
*/
@Deprecated
public void setCalibError(double avgErrorPx, double errorStdDevPx) {
this.avgErrorPx = avgErrorPx;
this.errorStdDevPx = errorStdDevPx;
}

/**
* Assigns calibration error properties of the simulated camera.
*
* @param errorStdDevPx Pixel error standard deviation
*/
public void setCalibError(double errorStdDevPx) {
this.errorStdDevPx = errorStdDevPx;
}

Expand Down Expand Up @@ -309,7 +289,7 @@ public double getLatencyStdDevMs() {
public SimCameraProperties copy() {
var newProp = new SimCameraProperties();
newProp.setCalibration(resWidth, resHeight, camIntrinsics, distCoeffs);
newProp.setCalibError(avgErrorPx, errorStdDevPx);
newProp.setCalibError(errorStdDevPx);
newProp.setFPS(getFPS());
newProp.setExposureTimeMs(exposureTimeMs);
newProp.setAvgLatencyMs(avgLatencyMs);
Expand Down Expand Up @@ -559,13 +539,13 @@ else if (!Double.isNaN(inter1)) {

/** Returns these points after applying this camera's estimated noise. */
public Point[] estPixelNoise(Point[] points) {
if (avgErrorPx == 0 && errorStdDevPx == 0) return points;
if (errorStdDevPx == 0) return points;

Point[] noisyPts = new Point[points.length];
for (int i = 0; i < points.length; i++) {
var p = points[i];
// error pixels in random direction
double error = avgErrorPx + rand.nextGaussian() * errorStdDevPx;
double error = rand.nextGaussian() * errorStdDevPx;
double errorAngle = rand.nextDouble() * 2 * Math.PI - Math.PI;
noisyPts[i] =
new Point(p.x + error * Math.cos(errorAngle), p.y + error * Math.sin(errorAngle));
Expand Down Expand Up @@ -622,7 +602,7 @@ public static SimCameraProperties PI4_LIFECAM_320_240() {
0,
0,
0));
prop.setCalibError(0.21, 0.0124);
prop.setCalibError(0.0124);
prop.setFPS(30);
prop.setAvgLatencyMs(30);
prop.setLatencyStdDevMs(10);
Expand Down Expand Up @@ -656,7 +636,7 @@ public static SimCameraProperties PI4_LIFECAM_640_480() {
0,
0,
0));
prop.setCalibError(0.26, 0.046);
prop.setCalibError(0.046);
prop.setFPS(15);
prop.setAvgLatencyMs(65);
prop.setLatencyStdDevMs(15);
Expand Down Expand Up @@ -689,7 +669,7 @@ public static SimCameraProperties LL2_640_480() {
0,
0,
0));
prop.setCalibError(0.25, 0.05);
prop.setCalibError(0.05);
prop.setFPS(15);
prop.setAvgLatencyMs(35);
prop.setLatencyStdDevMs(8);
Expand Down Expand Up @@ -723,7 +703,7 @@ public static SimCameraProperties LL2_960_720() {
0,
0,
0));
prop.setCalibError(0.35, 0.10);
prop.setCalibError(0.10);
prop.setFPS(10);
prop.setAvgLatencyMs(50);
prop.setLatencyStdDevMs(15);
Expand Down Expand Up @@ -757,7 +737,7 @@ public static SimCameraProperties LL2_1280_720() {
0,
0,
0));
prop.setCalibError(0.37, 0.06);
prop.setCalibError(0.06);
prop.setFPS(7);
prop.setAvgLatencyMs(60);
prop.setLatencyStdDevMs(20);
Expand Down
Loading