/* * MIT License * * Copyright (c) PhotonVision * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal * in the Software without restriction, including without limitation the rights * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell * copies of the Software, and to permit persons to whom the Software is * furnished to do so, subject to the following conditions: * * The above copyright notice and this permission notice shall be included in all * copies or substantial portions of the Software. * * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE * SOFTWARE. */ package org.photonvision.simulation; import com.fasterxml.jackson.databind.ObjectMapper; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.Matrix; import edu.wpi.first.math.Nat; import edu.wpi.first.math.Pair; import edu.wpi.first.math.VecBuilder; import edu.wpi.first.math.Vector; import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Rotation3d; import edu.wpi.first.math.geometry.Translation3d; import edu.wpi.first.math.numbers.*; import edu.wpi.first.wpilibj.DriverStation; import java.io.IOException; import java.nio.file.Path; import java.util.ArrayList; import java.util.List; import java.util.Random; import org.ejml.data.DMatrix3; import org.ejml.dense.fixed.CommonOps_DDF3; import org.opencv.core.MatOfPoint2f; import org.opencv.core.Point; import org.opencv.imgproc.Imgproc; import org.photonvision.estimation.OpenCVHelp; import org.photonvision.estimation.RotTrlTransform3d; /** * Calibration and performance values for this camera. * *
The resolution will affect the accuracy of projected(3d to 2d) target corners and similarly * the severity of image noise on estimation(2d to 3d). * *
The camera intrinsics and distortion coefficients describe the results of calibration, and how * to map between 3d field points and 2d image points. * *
The performance values (framerate/exposure time, latency) determine how often results should
* be updated and with how much latency in simulation. High exposure time causes motion blur which
* can inhibit target detection while moving. Note that latency estimation does not account for
* network latency and the latency reported will always be perfect.
*/
public class SimCameraProperties {
private final Random rand = new Random();
// calibration
private int resWidth;
private int resHeight;
private Matrix Note that this angle is naively computed and may be incorrect. See {@link
* #getCorrectedPixelRot(Point)}.
*/
public Rotation2d getPixelPitch(double pixelY) {
double fy = camIntrinsics.get(1, 1);
// account for principal point not being centered
double cy = camIntrinsics.get(1, 2);
double yOffset = cy - pixelY;
return new Rotation2d(fy, -yOffset);
}
/**
* Finds the yaw and pitch to the given image point. Yaw is positive left, and pitch is positive
* down.
*
* Note that pitch is naively computed and may be incorrect. See {@link
* #getCorrectedPixelRot(Point)}.
*/
public Rotation3d getPixelRot(Point point) {
return new Rotation3d(
0, getPixelPitch(point.y).getRadians(), getPixelYaw(point.x).getRadians());
}
/**
* Gives the yaw and pitch of the line intersecting the camera lens and the given pixel
* coordinates on the sensor. Yaw is positive left, and pitch positive down.
*
* The pitch traditionally calculated from pixel offsets do not correctly account for non-zero
* values of yaw because of perspective distortion (not to be confused with lens distortion)-- for
* example, the pitch angle is naively calculated as:
*
* The line is parametrized so any of its points config.json file. This is only the
* resolution, camera intrinsics, distortion coefficients, and average/std. dev. pixel error.
* Other camera properties must be set.
*
* @param path Path to the config.json 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.
*/
public SimCameraProperties(String path, int width, int height) throws IOException {
this(Path.of(path), width, height);
}
/**
* Reads camera properties from a photonvision config.json file. This is only the
* resolution, camera intrinsics, distortion coefficients, and average/std. dev. pixel error.
* Other camera properties must be set.
*
* @param path Path to the config.json 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.
*/
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("cameraExtrinsics").get("data");
double[] jsonDistortion = new double[jsonDistortNode.size()];
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,
Matrix.mat(Nat.N3(), Nat.N3()).fill(jsonIntrinsics),
Matrix.mat(Nat.N5(), Nat.N1()).fill(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");
}
public void setRandomSeed(long seed) {
rand.setSeed(seed);
}
public void 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(
"Requested invalid FOV! Clamping between (1, 179) degrees...", false);
}
double resDiag = Math.sqrt(resWidth * resWidth + resHeight * resHeight);
double diagRatio = Math.tan(fovDiag.getRadians() / 2);
var fovWidth = new Rotation2d(Math.atan(diagRatio * (resWidth / resDiag)) * 2);
var fovHeight = new Rotation2d(Math.atan(diagRatio * (resHeight / resDiag)) * 2);
// assume no distortion
var distCoeff = VecBuilder.fill(0, 0, 0, 0, 0);
// assume centered principal point (pixels)
double cx = resWidth / 2.0 - 0.5;
double cy = resHeight / 2.0 - 0.5;
// use given fov to determine focal point (pixels)
double fx = cx / Math.tan(fovWidth.getRadians() / 2.0);
double fy = cy / Math.tan(fovHeight.getRadians() / 2.0);
// create camera intrinsics matrix
var camIntrinsics = Matrix.mat(Nat.N3(), Nat.N3()).fill(fx, 0, cx, 0, fy, cy, 0, 0, 1);
setCalibration(resWidth, resHeight, camIntrinsics, distCoeff);
}
public void setCalibration(
int resWidth, int resHeight, Matrixpitch = arctan(pixel y offset / focal length y)
*
* However, using focal length as a side of the associated right triangle is not correct when the
* pixel x value is not 0, because the distance from this pixel (projected on the x-axis) to the
* camera lens increases. Projecting a line back out of the camera with these naive angles will
* not intersect the 3d point that was originally projected into this 2d pixel. Instead, this
* length should be:
*
* focal length y ⟶ (focal length y / cos(arctan(pixel x offset / focal length x)))
*
* @return Rotation3d with yaw and pitch of the line projected out of the camera from the given
* pixel (roll is zero).
*/
public Rotation3d getCorrectedPixelRot(Point point) {
double fx = camIntrinsics.get(0, 0);
double cx = camIntrinsics.get(0, 2);
double xOffset = cx - point.x;
double fy = camIntrinsics.get(1, 1);
double cy = camIntrinsics.get(1, 2);
double yOffset = cy - point.y;
// calculate yaw normally
var yaw = new Rotation2d(fx, xOffset);
// correct pitch based on yaw
var pitch = new Rotation2d(fy / Math.cos(Math.atan(xOffset / fx)), -yOffset);
return new Rotation3d(0, pitch.getRadians(), yaw.getRadians());
}
public Rotation2d getHorizFOV() {
// sum of FOV left and right principal point
var left = getPixelYaw(0);
var right = getPixelYaw(resWidth);
return left.minus(right);
}
public Rotation2d getVertFOV() {
// sum of FOV above and below principal point
var above = getPixelPitch(0);
var below = getPixelPitch(resHeight);
return below.minus(above);
}
public Rotation2d getDiagFOV() {
return new Rotation2d(Math.hypot(getHorizFOV().getRadians(), getVertFOV().getRadians()));
}
/**
* Determines where the line segment defined by the two given translations intersects the camera's
* frustum/field-of-vision, if at all.
*
* p = t * (b - a) + a. This method
* returns these values of t, minimum first, defining the region of the line segment which is
* visible in the frustum. If both ends of the line segment are visible, this simply returns {0,
* 1}. If, for example, point b is visible while a is not, and half of the line segment is inside
* the camera frustum, {0.5, 1} would be returned.
*
* @param camRt The change in basis from world coordinates to camera coordinates. See {@link
* RotTrlTransform3d#makeRelativeTo(Pose3d)}.
* @param a The initial translation of the line
* @param b The final translation of the line
* @return A Pair of Doubles. The values may be null:
*
*
*/
public Pair