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 3 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,8 +73,10 @@ public class SimCameraProperties {
private int resHeight;
private Matrix<N3, N3> camIntrinsics;
private Matrix<N8, N1> distCoeffs;
private double avgErrorPx;
private double errorStdDevPx;
private double avgErrorPxX;
private double errorStdDevPxX;
private double avgErrorPxY;
private double errorStdDevPxY;
// performance
private double frameSpeedMs = 0;
private double exposureTimeMs = 0;
Expand Down Expand Up @@ -126,32 +128,9 @@ public SimCameraProperties(Path path, int width, int height) throws IOException
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);

setupCalibration(calib, jsonWidth, jsonHeight);
setupCalibrationError(calib);
success = true;
}
} catch (Exception e) {
Expand All @@ -160,6 +139,94 @@ public SimCameraProperties(Path path, int width, int height) throws IOException
if (!success) throw new IOException("Requested resolution not found in calibration");
}

private void setupCalibration(JsonNode calib, int jsonWidth, int jsonHeight) {
// 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();
}

// 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));
}

private void setupCalibrationError(JsonNode calib) {
var jsonViewErrors = calib.get("perViewErrors");
var jsonErrorStdDev = calib.get("standardDeviation");
double jsonAvgErrorX = 0;
double jsonAvgErrorY = 0;
double jsonErrorStdDevX = 0;
double jsonErrorStdDevY = 0;

if (jsonViewErrors != null && jsonErrorStdDev != null) {
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Should I bother with a fallback for the existing logic?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Probably unnecessary.

The load-by-path option here has not really been used since the SQLite storage was implemented and a calibration json was no longer easily accessible. Has this changed?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

There is still currently no longer any way to access a camera config file no. The calibration json file is still easy to get. Let's kill this feature if we don't need it anymore?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Happy to yoink config file support if that's what we're looking to do here.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I've deprecated the two applicable constructors to this feature.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Given that we dropped support for this feature from the backend back in 2023, and the ctor is now a no-op, let's just delete them? Or open to your thoughts @amquake

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Oh, it seems you can export the camera calibration json again now? That would make this constructor useful. It's just to load the resolution/intrinsics/distortion/reprojection error from the exported json instead of copying those values over manually.

double jsonAvgError = 0;
for (int j = 0; j < jsonViewErrors.size(); j++) {
jsonAvgError += jsonViewErrors.get(j).asDouble();
}
jsonAvgError /= jsonViewErrors.size();

jsonAvgErrorX = jsonAvgError;
jsonAvgErrorY = jsonAvgError;
jsonErrorStdDevX = jsonErrorStdDev.asDouble();
jsonErrorStdDevY = jsonErrorStdDev.asDouble();
} else {
double jsonAvgError = 0;
for (int j = 0; j < jsonViewErrors.size(); j++) {
jsonAvgError += jsonViewErrors.get(j).asDouble();
}
jsonAvgError /= jsonViewErrors.size();

var jsonObservations = calib.get("observations");
int observationCount = 0;
for (int j = 0; j < jsonObservations.size(); j++) {
var jsonReprojectionError = jsonObservations.get(j).get("reprojectionErrors");
observationCount += jsonReprojectionError.size();
}

double[] jsonErrorX = new double[observationCount];
double[] jsonErrorY = new double[observationCount];
int observationIndex = 0;
for (int j = 0; j < jsonObservations.size(); j++) {
var jsonReprojectionError = jsonObservations.get(j).get("reprojectionErrors");
for (int k = 0; k < jsonReprojectionError.size(); k++) {
jsonErrorX[observationIndex] = jsonReprojectionError.get(k).get("x").asDouble();
jsonErrorY[observationIndex] = jsonReprojectionError.get(k).get("y").asDouble();

observationIndex += 1;
}
}

double jsonAvgErrorX = 0;
double jsonAvgErrorY = 0;
for (int j = 0; j < observationCount; j++) {
jsonAvgErrorX += jsonErrorX[j] / observationCount;
jsonAvgErrorY += jsonErrorY[j] / observationCount;
}

double jsonErrorStdDevX = 0;
double jsonErrorStdDevY = 0;
for (int j = 0; j < observationCount; j++) {
jsonErrorStdDevX += Math.pow(jsonErrorX[j] - jsonAvgErrorX, 2) / observationCount;
jsonErrorStdDevY += Math.pow(jsonErrorY[j] - jsonAvgErrorY, 2) / observationCount;
}
jsonErrorStdDevX = Math.sqrt(jsonErrorStdDevX);
jsonErrorStdDevY = Math.sqrt(jsonErrorStdDevY);
}

setCalibError(jsonAvgErrorX, jsonErrorStdDevX, jsonAvgErrorY, jsonErrorStdDevY);
}

public void setRandomSeed(long seed) {
rand.setSeed(seed);
}
Expand Down Expand Up @@ -224,9 +291,11 @@ public void setCalibration(
}
}

public void setCalibError(double avgErrorPx, double errorStdDevPx) {
this.avgErrorPx = avgErrorPx;
this.errorStdDevPx = errorStdDevPx;
public void setCalibError(double avgErrorPxX, double errorStdDevPxX, double avgErrorPxY, double errorStdDevPxY) {
this.avgErrorPxX = avgErrorPxX;
this.errorStdDevPxX = errorStdDevPxX;
this.avgErrorPxY = avgErrorPxY;
this.errorStdDevPxY = errorStdDevPxY;
}

/**
Expand Down Expand Up @@ -565,10 +634,10 @@ public Point[] estPixelNoise(Point[] points) {
for (int i = 0; i < points.length; i++) {
var p = points[i];
// error pixels in random direction
double error = avgErrorPx + rand.nextGaussian() * errorStdDevPx;
double errorAngle = rand.nextDouble() * 2 * Math.PI - Math.PI;
double errorX = avgErrorPxX + rand.nextGaussian() * errorStdDevPxX;
double errorY = avgErrorPxY + rand.nextGaussian() * errorStdDevPxY;
noisyPts[i] =
new Point(p.x + error * Math.cos(errorAngle), p.y + error * Math.sin(errorAngle));
new Point(p.x + errorX, p.y + errorY);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

IIRC the previous "average error" from calibration seemed to report the average absolute error. The previous way of estimating noise tries to use both the average (absolute) error and standard deviation which is pretty goofy. I'm not sure these numbers even really make sense to use in the first place, considering they measure solely the reprojection error of the calibrated instrinsics.

Anyway, it probably makes more sense to just consider the corner pixel normally distributed with given standard deviation. Meaning, just remove (deprecate) the average view error from SimCameraProperties. This will noticeably lower the noise currently seen by whatever values are used, but the simulation already seemed to overestimate it.

Copy link
Contributor Author

@jlmcmchl jlmcmchl Jan 2, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I figured I'd try separating x and y noise because I didn't want to assume that the shape of the pixel noise distribution was circular, but with removing support for file based configs there isn't much of a reason to keep it around. I found it to be useful because we could leverage existing data rather than come up with those values independent of calibration data.

In this changeset I opted to revert the separation of the two because otherwise we'd be deprecating setCalibError(double avgErrorPx, double errorStdDevPx) and introducing setCalibError(double errorStdDevPxX, double errorStdDevPxY). It's always easy to reintroduce at a better time,

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think assuming the noise is circular/isotropic is valid here. Again, this is using the reprojection error of the calibration as a baseline for estimating corner detection noise, which would make doing more than just a constant, normal circular distribution difficult. That would imply calculating the noise based on the location in the image, which seems excessive.

}
return noisyPts;
}
Expand Down
Loading