001/* 002 * MIT License 003 * 004 * Copyright (c) PhotonVision 005 * 006 * Permission is hereby granted, free of charge, to any person obtaining a copy 007 * of this software and associated documentation files (the "Software"), to deal 008 * in the Software without restriction, including without limitation the rights 009 * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 010 * copies of the Software, and to permit persons to whom the Software is 011 * furnished to do so, subject to the following conditions: 012 * 013 * The above copyright notice and this permission notice shall be included in all 014 * copies or substantial portions of the Software. 015 * 016 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 017 * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 018 * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 019 * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 020 * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 021 * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 022 * SOFTWARE. 023 */ 024 025package org.photonvision.simulation; 026 027import io.avaje.json.JsonIoException; 028import io.avaje.jsonb.Json; 029import io.avaje.jsonb.Jsonb; 030import java.io.FileInputStream; 031import java.io.IOException; 032import java.nio.file.Path; 033import java.util.ArrayList; 034import java.util.Arrays; 035import java.util.List; 036import java.util.Random; 037import org.ejml.data.DMatrix3; 038import org.ejml.dense.fixed.CommonOps_DDF3; 039import org.opencv.core.MatOfPoint2f; 040import org.opencv.core.Point; 041import org.opencv.imgproc.Imgproc; 042import org.photonvision.estimation.OpenCVHelp; 043import org.photonvision.estimation.RotTrlTransform3d; 044import org.wpilib.driverstation.DriverStationErrors; 045import org.wpilib.math.geometry.Pose3d; 046import org.wpilib.math.geometry.Rotation2d; 047import org.wpilib.math.geometry.Rotation3d; 048import org.wpilib.math.geometry.Translation3d; 049import org.wpilib.math.linalg.MatBuilder; 050import org.wpilib.math.linalg.Matrix; 051import org.wpilib.math.linalg.VecBuilder; 052import org.wpilib.math.linalg.Vector; 053import org.wpilib.math.numbers.*; 054import org.wpilib.math.util.Nat; 055import org.wpilib.math.util.Pair; 056 057/** 058 * Calibration and performance values for this camera. 059 * 060 * <p>The resolution will affect the accuracy of projected(3d to 2d) target corners and similarly 061 * the severity of image noise on estimation(2d to 3d). 062 * 063 * <p>The camera intrinsics and distortion coefficients describe the results of calibration, and how 064 * to map between 3d field points and 2d image points. 065 * 066 * <p>The performance values (framerate/exposure time, latency) determine how often results should 067 * be updated and with how much latency in simulation. High exposure time causes motion blur which 068 * can inhibit target detection while moving. Note that latency estimation does not account for 069 * network latency and the latency reported will always be perfect. 070 */ 071public class SimCameraProperties { 072 @Json 073 record SimCameraData(SimCameraCalibrationData[] calibrations) { 074 @Json 075 record SimCameraCalibrationData( 076 ResolutionData resolution, 077 CameraIntrinsicsData cameraIntrinsics, 078 DistortionCoefficients distCoeffs, 079 double[] perViewErrors, 080 double standardDeviation) { 081 @Json 082 record ResolutionData(int width, int height) {} 083 084 @Json 085 record CameraIntrinsicsData(double[] data) {} 086 087 @Json 088 record DistortionCoefficients(double[] data) {} 089 } 090 } 091 092 private final Random rand = new Random(); 093 // calibration 094 private int resWidth; 095 private int resHeight; 096 private Matrix<N3, N3> camIntrinsics; 097 private Matrix<N8, N1> distCoeffs; 098 private double avgErrorPx; 099 private double errorStdDevPx; 100 // performance 101 private double frameSpeedMs = 0; 102 private double exposureTimeMs = 0; 103 private double avgLatencyMs = 0; 104 private double latencyStdDevMs = 0; 105 // util 106 private final List<DMatrix3> viewplanes = new ArrayList<>(); 107 108 /** Default constructor which is the same as {@link #PERFECT_90DEG} */ 109 public SimCameraProperties() { 110 setCalibration(960, 720, Rotation2d.fromDegrees(90)); 111 } 112 113 /** 114 * Reads camera properties from a PhotonVision <code>config.json</code> file. This is only the 115 * resolution, camera intrinsics, distortion coefficients, and average/std. dev. pixel error. 116 * Other camera properties must be set. 117 * 118 * @param path Path to the <code>config.json</code> file 119 * @param width The width of the desired resolution in the JSON 120 * @param height The height of the desired resolution in the JSON 121 * @throws IOException If reading the JSON fails, either from an invalid path or a missing/invalid 122 * calibrated resolution. 123 */ 124 public SimCameraProperties(String path, int width, int height) throws IOException { 125 this(Path.of(path), width, height); 126 } 127 128 /** 129 * Reads camera properties from a PhotonVision <code>config.json</code> file. This is only the 130 * resolution, camera intrinsics, distortion coefficients, and average/std. dev. pixel error. 131 * Other camera properties must be set. 132 * 133 * @param path Path to the <code>config.json</code> file 134 * @param width The width of the desired resolution in the JSON 135 * @param height The height of the desired resolution in the JSON 136 * @throws IOException If reading the JSON fails, either from an invalid path or a missing/invalid 137 * calibrated resolution. 138 */ 139 public SimCameraProperties(Path path, int width, int height) throws IOException { 140 SimCameraData data; 141 try (var stream = new FileInputStream(path.toFile())) { 142 data = Jsonb.instance().type(SimCameraData.class).fromJson(stream); 143 } catch (JsonIoException e) { 144 throw new IOException("Invalid calibration JSON", e); 145 } 146 boolean success = false; 147 for (var calib : data.calibrations) { 148 // check if this calibration entry is our desired resolution 149 if (calib.resolution.width != width || calib.resolution.height != height) continue; 150 // get the relevant calibration values 151 double avgViewError = Arrays.stream(calib.perViewErrors).average().orElse(0); 152 // assign the read JSON values to this CameraProperties 153 setCalibration( 154 calib.resolution.width, 155 calib.resolution.height, 156 MatBuilder.fill(Nat.N3(), Nat.N3(), calib.cameraIntrinsics.data), 157 MatBuilder.fill(Nat.N8(), Nat.N1(), calib.distCoeffs.data)); 158 setCalibError(avgViewError, calib.standardDeviation); 159 success = true; 160 } 161 if (!success) throw new IOException("Requested resolution not found in calibration"); 162 } 163 164 public SimCameraProperties setRandomSeed(long seed) { 165 rand.setSeed(seed); 166 return this; 167 } 168 169 public SimCameraProperties setCalibration(int resWidth, int resHeight, Rotation2d fovDiag) { 170 if (fovDiag.getDegrees() < 1 || fovDiag.getDegrees() > 179) { 171 fovDiag = Rotation2d.fromDegrees(Math.clamp(fovDiag.getDegrees(), 1, 179)); 172 DriverStationErrors.reportError( 173 "Requested invalid FOV! Clamping between (1, 179) degrees...", false); 174 } 175 double resDiag = Math.hypot(resWidth, resHeight); 176 double diagRatio = Math.tan(fovDiag.getRadians() / 2); 177 var fovWidth = new Rotation2d(Math.atan(diagRatio * (resWidth / resDiag)) * 2); 178 var fovHeight = new Rotation2d(Math.atan(diagRatio * (resHeight / resDiag)) * 2); 179 180 // assume no distortion 181 var distCoeff = VecBuilder.fill(0, 0, 0, 0, 0, 0, 0, 0); 182 183 // assume centered principal point (pixels) 184 double cx = resWidth / 2.0 - 0.5; 185 double cy = resHeight / 2.0 - 0.5; 186 187 // use given fov to determine focal point (pixels) 188 double fx = cx / Math.tan(fovWidth.getRadians() / 2.0); 189 double fy = cy / Math.tan(fovHeight.getRadians() / 2.0); 190 191 // create camera intrinsics matrix 192 var camIntrinsics = MatBuilder.fill(Nat.N3(), Nat.N3(), fx, 0, cx, 0, fy, cy, 0, 0, 1); 193 setCalibration(resWidth, resHeight, camIntrinsics, distCoeff); 194 195 return this; 196 } 197 198 public SimCameraProperties setCalibration( 199 int resWidth, int resHeight, Matrix<N3, N3> camIntrinsics, Matrix<N8, N1> distCoeffs) { 200 this.resWidth = resWidth; 201 this.resHeight = resHeight; 202 this.camIntrinsics = camIntrinsics; 203 this.distCoeffs = distCoeffs; 204 205 // left, right, up, and down view planes 206 Translation3d[] p = { 207 new Translation3d( 208 1, new Rotation3d(0, 0, getPixelYaw(0).plus(new Rotation2d(-Math.PI / 2)).getRadians())), 209 new Translation3d( 210 1, 211 new Rotation3d( 212 0, 0, getPixelYaw(resWidth).plus(new Rotation2d(Math.PI / 2)).getRadians())), 213 new Translation3d( 214 1, new Rotation3d(0, getPixelPitch(0).plus(new Rotation2d(Math.PI / 2)).getRadians(), 0)), 215 new Translation3d( 216 1, 217 new Rotation3d( 218 0, getPixelPitch(resHeight).plus(new Rotation2d(-Math.PI / 2)).getRadians(), 0)) 219 }; 220 viewplanes.clear(); 221 for (Translation3d translation3d : p) { 222 viewplanes.add( 223 new DMatrix3(translation3d.getX(), translation3d.getY(), translation3d.getZ())); 224 } 225 226 return this; 227 } 228 229 public SimCameraProperties setCalibError(double avgErrorPx, double errorStdDevPx) { 230 this.avgErrorPx = avgErrorPx; 231 this.errorStdDevPx = errorStdDevPx; 232 return this; 233 } 234 235 /** 236 * Sets the simulated FPS for this camera. 237 * 238 * @param fps The average frames per second the camera should process at. <b>Exposure time limits 239 * FPS if set!</b> 240 * @return This camera properties object for use in chaining 241 */ 242 public SimCameraProperties setFPS(double fps) { 243 frameSpeedMs = Math.max(1000.0 / fps, exposureTimeMs); 244 245 return this; 246 } 247 248 /** 249 * Sets the simulated exposure time for this camera. 250 * 251 * @param exposureTimeMs The amount of time the "shutter" is open for one frame. Affects motion 252 * blur. <b>Frame speed(from FPS) is limited to this!</b> 253 * @return This camera properties object for use in chaining 254 */ 255 public SimCameraProperties setExposureTimeMs(double exposureTimeMs) { 256 this.exposureTimeMs = exposureTimeMs; 257 frameSpeedMs = Math.max(frameSpeedMs, exposureTimeMs); 258 259 return this; 260 } 261 262 /** 263 * Sets the simulated latency for this camera. 264 * 265 * @param avgLatencyMs The average latency (from image capture to data published) in milliseconds 266 * a frame should have 267 * @return This camera properties object for use in chaining 268 */ 269 public SimCameraProperties setAvgLatencyMs(double avgLatencyMs) { 270 this.avgLatencyMs = avgLatencyMs; 271 272 return this; 273 } 274 275 /** 276 * Sets the simulated latency variation for this camera. 277 * 278 * @param latencyStdDevMs The standard deviation in milliseconds of the latency 279 * @return This camera properties object for use in chaining 280 */ 281 public SimCameraProperties setLatencyStdDevMs(double latencyStdDevMs) { 282 this.latencyStdDevMs = latencyStdDevMs; 283 284 return this; 285 } 286 287 /** 288 * Gets the width of the simulated camera image. 289 * 290 * @return The width in pixels 291 */ 292 public int getResWidth() { 293 return resWidth; 294 } 295 296 /** 297 * Gets the height of the simulated camera image. 298 * 299 * @return The height in pixels 300 */ 301 public int getResHeight() { 302 return resHeight; 303 } 304 305 /** 306 * Gets the area of the simulated camera image. 307 * 308 * @return The area in pixels 309 */ 310 public int getResArea() { 311 return resWidth * resHeight; 312 } 313 314 /** Width:height */ 315 public double getAspectRatio() { 316 return (double) resWidth / resHeight; 317 } 318 319 public Matrix<N3, N3> getIntrinsics() { 320 return camIntrinsics.copy(); 321 } 322 323 /** 324 * Returns the camera calibration's distortion coefficients, in OPENCV8 form. Higher-order terms 325 * are set to 0 326 * 327 * @return The distortion coefficients in an 8d vector 328 */ 329 public Vector<N8> getDistCoeffs() { 330 return new Vector<>(distCoeffs); 331 } 332 333 /** 334 * Gets the FPS of the simulated camera. 335 * 336 * @return The FPS 337 */ 338 public double getFPS() { 339 return 1000.0 / frameSpeedMs; 340 } 341 342 /** 343 * Gets the time per frame of the simulated camera. 344 * 345 * @return The time per frame in milliseconds 346 */ 347 public double getFrameSpeedMs() { 348 return frameSpeedMs; 349 } 350 351 /** 352 * Gets the exposure time of the simulated camera. 353 * 354 * @return The exposure time in milliseconds 355 */ 356 public double getExposureTimeMs() { 357 return exposureTimeMs; 358 } 359 360 /** 361 * Gets the average latency of the simulated camera. 362 * 363 * @return The average latency in milliseconds 364 */ 365 public double getAvgLatencyMs() { 366 return avgLatencyMs; 367 } 368 369 /** 370 * Gets the time per frame of the simulated camera. 371 * 372 * @return The time per frame in milliseconds 373 */ 374 public double getLatencyStdDevMs() { 375 return latencyStdDevMs; 376 } 377 378 /** 379 * Returns a copy of the camera properties. 380 * 381 * @return The copied camera properties 382 */ 383 public SimCameraProperties copy() { 384 var newProp = new SimCameraProperties(); 385 newProp.setCalibration(resWidth, resHeight, camIntrinsics, distCoeffs); 386 newProp.setCalibError(avgErrorPx, errorStdDevPx); 387 newProp.setFPS(getFPS()); 388 newProp.setExposureTimeMs(exposureTimeMs); 389 newProp.setAvgLatencyMs(avgLatencyMs); 390 newProp.setLatencyStdDevMs(latencyStdDevMs); 391 return newProp; 392 } 393 394 /** 395 * The percentage (0 - 100) of this camera's resolution the contour takes up in pixels of the 396 * image. 397 * 398 * @param points Points of the contour 399 * @return The percentage 400 */ 401 public double getContourAreaPercent(Point[] points) { 402 return Imgproc.contourArea(new MatOfPoint2f(OpenCVHelp.getConvexHull(points))) 403 / getResArea() 404 * 100; 405 } 406 407 /** The yaw from the principal point of this camera to the pixel x value. Positive values left. */ 408 public Rotation2d getPixelYaw(double pixelX) { 409 double fx = camIntrinsics.get(0, 0); 410 // account for principal point not being centered 411 double cx = camIntrinsics.get(0, 2); 412 double xOffset = cx - pixelX; 413 return new Rotation2d(fx, xOffset); 414 } 415 416 /** 417 * The pitch from the principal point of this camera to the pixel y value. Pitch is positive down. 418 * 419 * <p>Note that this angle is naively computed and may be incorrect. See {@link 420 * #getCorrectedPixelRot(Point)}. 421 */ 422 public Rotation2d getPixelPitch(double pixelY) { 423 double fy = camIntrinsics.get(1, 1); 424 // account for principal point not being centered 425 double cy = camIntrinsics.get(1, 2); 426 double yOffset = cy - pixelY; 427 return new Rotation2d(fy, -yOffset); 428 } 429 430 /** 431 * Finds the yaw and pitch to the given image point. Yaw is positive left, and pitch is positive 432 * down. 433 * 434 * <p>Note that pitch is naively computed and may be incorrect. See {@link 435 * #getCorrectedPixelRot(Point)}. 436 */ 437 public Rotation3d getPixelRot(Point point) { 438 return new Rotation3d( 439 0, getPixelPitch(point.y).getRadians(), getPixelYaw(point.x).getRadians()); 440 } 441 442 /** 443 * Gives the yaw and pitch of the line intersecting the camera lens and the given pixel 444 * coordinates on the sensor. Yaw is positive left, and pitch positive down. 445 * 446 * <p>The pitch traditionally calculated from pixel offsets do not correctly account for non-zero 447 * values of yaw because of perspective distortion (not to be confused with lens distortion)-- for 448 * example, the pitch angle is naively calculated as: 449 * 450 * <pre>pitch = arctan(pixel y offset / focal length y)</pre> 451 * 452 * However, using focal length as a side of the associated right triangle is not correct when the 453 * pixel x value is not 0, because the distance from this pixel (projected on the x-axis) to the 454 * camera lens increases. Projecting a line back out of the camera with these naive angles will 455 * not intersect the 3d point that was originally projected into this 2d pixel. Instead, this 456 * length should be: 457 * 458 * <pre>focal length y ⟶ (focal length y / cos(arctan(pixel x offset / focal length x)))</pre> 459 * 460 * @return Rotation3d with yaw and pitch of the line projected out of the camera from the given 461 * pixel (roll is zero). 462 */ 463 public Rotation3d getCorrectedPixelRot(Point point) { 464 double fx = camIntrinsics.get(0, 0); 465 double cx = camIntrinsics.get(0, 2); 466 double xOffset = cx - point.x; 467 468 double fy = camIntrinsics.get(1, 1); 469 double cy = camIntrinsics.get(1, 2); 470 double yOffset = cy - point.y; 471 472 // calculate yaw normally 473 var yaw = new Rotation2d(fx, xOffset); 474 // correct pitch based on yaw 475 var pitch = new Rotation2d(fy / Math.cos(Math.atan(xOffset / fx)), -yOffset); 476 477 return new Rotation3d(0, pitch.getRadians(), yaw.getRadians()); 478 } 479 480 public Rotation2d getHorizFOV() { 481 // sum of FOV left and right principal point 482 var left = getPixelYaw(0); 483 var right = getPixelYaw(resWidth); 484 return left.minus(right); 485 } 486 487 public Rotation2d getVertFOV() { 488 // sum of FOV above and below principal point 489 var above = getPixelPitch(0); 490 var below = getPixelPitch(resHeight); 491 return below.minus(above); 492 } 493 494 public Rotation2d getDiagFOV() { 495 return new Rotation2d(Math.hypot(getHorizFOV().getRadians(), getVertFOV().getRadians())); 496 } 497 498 /** 499 * Determines where the line segment defined by the two given translations intersects the camera's 500 * frustum/field-of-vision, if at all. 501 * 502 * <p>The line is parametrized so any of its points <code>p = t * (b - a) + a</code>. This method 503 * returns these values of t, minimum first, defining the region of the line segment which is 504 * visible in the frustum. If both ends of the line segment are visible, this simply returns {0, 505 * 1}. If, for example, point b is visible while a is not, and half of the line segment is inside 506 * the camera frustum, {0.5, 1} would be returned. 507 * 508 * @param camRt The change in basis from world coordinates to camera coordinates. See {@link 509 * RotTrlTransform3d#makeRelativeTo(Pose3d)}. 510 * @param a The initial translation of the line 511 * @param b The final translation of the line 512 * @return A Pair of Doubles. The values may be null: 513 * <ul> 514 * <li>{Double, Double} : Two parametrized values(t), minimum first, representing which 515 * segment of the line is visible in the camera frustum. 516 * <li>{Double, null} : One value(t) representing a single intersection point. For example, 517 * the line only intersects the intersection of two adjacent viewplanes. 518 * <li>{null, null} : No values. The line segment is not visible in the camera frustum. 519 * </ul> 520 */ 521 public Pair<Double, Double> getVisibleLine( 522 RotTrlTransform3d camRt, Translation3d a, Translation3d b) { 523 // translations relative to the camera 524 var rela = camRt.apply(a); 525 var relb = camRt.apply(b); 526 527 // check if both ends are behind camera 528 if (rela.getX() <= 0 && relb.getX() <= 0) return new Pair<>(null, null); 529 530 var av = new DMatrix3(rela.getX(), rela.getY(), rela.getZ()); 531 var bv = new DMatrix3(relb.getX(), relb.getY(), relb.getZ()); 532 // a to b 533 var abv = new DMatrix3(); 534 CommonOps_DDF3.subtract(bv, av, abv); 535 536 // check if the ends of the line segment are visible 537 boolean aVisible = true; 538 boolean bVisible = true; 539 for (DMatrix3 normal : viewplanes) { 540 double aVisibility = CommonOps_DDF3.dot(av, normal); 541 if (aVisibility < 0) aVisible = false; 542 double bVisibility = CommonOps_DDF3.dot(bv, normal); 543 if (bVisibility < 0) bVisible = false; 544 // both ends are outside at least one of the same viewplane 545 if (aVisibility <= 0 && bVisibility <= 0) return new Pair<>(null, null); 546 } 547 // both ends are inside frustum 548 if (aVisible && bVisible) return new Pair<>((double) 0, 1.0); 549 550 // parametrized (t=0 at a, t=1 at b) intersections with viewplanes 551 double[] intersections = {Double.NaN, Double.NaN, Double.NaN, Double.NaN}; 552 // intersection points 553 List<DMatrix3> ipts = new ArrayList<>(); 554 for (double val : intersections) ipts.add(null); 555 556 // find intersections 557 for (int i = 0; i < viewplanes.size(); i++) { 558 var normal = viewplanes.get(i); 559 560 // we want to know the value of t when the line intercepts this plane 561 // parametrized: v = t * ab + a, where v lies on the plane 562 // we can find the projection of a onto the plane normal 563 // a_projn = normal.times(av.dot(normal) / normal.dot(normal)); 564 var a_projn = new DMatrix3(); 565 CommonOps_DDF3.scale( 566 CommonOps_DDF3.dot(av, normal) / CommonOps_DDF3.dot(normal, normal), normal, a_projn); 567 // this projection lets us determine the scalar multiple t of ab where 568 // (t * ab + a) is a vector which lies on the plane 569 if (Math.abs(CommonOps_DDF3.dot(abv, a_projn)) < 1e-5) continue; // line is parallel to plane 570 intersections[i] = CommonOps_DDF3.dot(a_projn, a_projn) / -CommonOps_DDF3.dot(abv, a_projn); 571 572 // vector a to the viewplane 573 var apv = new DMatrix3(); 574 CommonOps_DDF3.scale(intersections[i], abv, apv); 575 // av + apv = intersection point 576 var intersectpt = new DMatrix3(); 577 CommonOps_DDF3.add(av, apv, intersectpt); 578 ipts.set(i, intersectpt); 579 580 // discard intersections outside the camera frustum 581 for (int j = 1; j < viewplanes.size(); j++) { 582 int oi = (i + j) % viewplanes.size(); 583 var onormal = viewplanes.get(oi); 584 // if the dot of the intersection point with any plane normal is negative, it is outside 585 if (CommonOps_DDF3.dot(intersectpt, onormal) < 0) { 586 intersections[i] = Double.NaN; 587 ipts.set(i, null); 588 break; 589 } 590 } 591 592 // discard duplicate intersections 593 if (ipts.get(i) == null) continue; 594 for (int j = i - 1; j >= 0; j--) { 595 var oipt = ipts.get(j); 596 if (oipt == null) continue; 597 var diff = new DMatrix3(); 598 CommonOps_DDF3.subtract(oipt, intersectpt, diff); 599 if (CommonOps_DDF3.elementMaxAbs(diff) < 1e-4) { 600 intersections[i] = Double.NaN; 601 ipts.set(i, null); 602 break; 603 } 604 } 605 } 606 607 // determine visible segment (minimum and maximum t) 608 double inter1 = Double.NaN; 609 double inter2 = Double.NaN; 610 for (double inter : intersections) { 611 if (!Double.isNaN(inter)) { 612 if (Double.isNaN(inter1)) inter1 = inter; 613 else inter2 = inter; 614 } 615 } 616 617 // two viewplane intersections 618 if (!Double.isNaN(inter2)) { 619 double max = Math.max(inter1, inter2); 620 double min = Math.min(inter1, inter2); 621 if (aVisible) min = 0; 622 if (bVisible) max = 1; 623 return new Pair<>(min, max); 624 } 625 // one viewplane intersection 626 else if (!Double.isNaN(inter1)) { 627 if (aVisible) return new Pair<>((double) 0, inter1); 628 if (bVisible) return new Pair<>(inter1, 1.0); 629 return new Pair<>(inter1, null); 630 } 631 // no intersections 632 else return new Pair<>(null, null); 633 } 634 635 /** 636 * Returns these points after applying this camera's estimated noise. 637 * 638 * @param points The points to add noise to 639 * @return The points with noise 640 */ 641 public Point[] estPixelNoise(Point[] points) { 642 if (avgErrorPx == 0 && errorStdDevPx == 0) return points; 643 644 Point[] noisyPts = new Point[points.length]; 645 for (int i = 0; i < points.length; i++) { 646 var p = points[i]; 647 // error pixels in random direction 648 double error = avgErrorPx + rand.nextGaussian() * errorStdDevPx; 649 double errorAngle = rand.nextDouble() * 2 * Math.PI - Math.PI; 650 noisyPts[i] = 651 new Point(p.x + error * Math.cos(errorAngle), p.y + error * Math.sin(errorAngle)); 652 } 653 return noisyPts; 654 } 655 656 /** 657 * Returns an estimation of a frame's processing latency with noise added. 658 * 659 * @return The latency estimate in milliseconds 660 */ 661 public double estLatencyMs() { 662 return Math.max(avgLatencyMs + rand.nextGaussian() * latencyStdDevMs, 0); 663 } 664 665 /** 666 * Estimates how long until the next frame should be processed. 667 * 668 * @return The estimated time until the next frame in milliseconds 669 */ 670 public double estMsUntilNextFrame() { 671 // exceptional processing latency blocks the next frame 672 return frameSpeedMs + Math.max(0, estLatencyMs() - frameSpeedMs); 673 } 674 675 // pre-calibrated example cameras 676 677 /** 678 * Creates a set of camera properties where the camera has a 960x720 resolution, 90 degree FOV, 679 * and is a "perfect" lagless camera. 680 * 681 * @return The properties for this theoretical camera 682 */ 683 public static SimCameraProperties PERFECT_90DEG() { 684 return new SimCameraProperties(); 685 } 686 687 /** 688 * Creates a set of camera properties matching those of Microsoft Lifecam running on a Raspberry 689 * Pi 4 at 320x240 resolution. 690 * 691 * <p>Note that this set of properties represents <i>a camera setup</i>, not <i>your camera 692 * setup</i>. Do not use these camera properties for any non-sim vision calculations, especially 693 * the calibration data. Always use your camera's calibration data to do vision calculations in 694 * non-sim environments. These properties exist as a sample that may be used to get representative 695 * data in sim. 696 * 697 * @return The properties for this camera setup 698 */ 699 public static SimCameraProperties PI4_LIFECAM_320_240() { 700 var prop = new SimCameraProperties(); 701 prop.setCalibration( 702 320, 703 240, 704 MatBuilder.fill( 705 Nat.N3(), 706 Nat.N3(), 707 // intrinsic 708 328.2733242048587, 709 0.0, 710 164.8190261141906, 711 0.0, 712 318.0609794305216, 713 123.8633838438093, 714 0.0, 715 0.0, 716 1.0), 717 VecBuilder.fill( // distort 718 0.09957946553445934, 719 -0.9166265114485799, 720 0.0019519890627236526, 721 -0.0036071725380870333, 722 1.5627234622420942, 723 0, 724 0, 725 0)); 726 prop.setCalibError(0.21, 0.0124); 727 prop.setFPS(30); 728 prop.setAvgLatencyMs(30); 729 prop.setLatencyStdDevMs(10); 730 return prop; 731 } 732 733 /** 734 * Creates a set of camera properties matching those of Microsoft Lifecam running on a Raspberry 735 * Pi 4 at 640x480 resolution. 736 * 737 * <p>Note that this set of properties represents <i>a camera setup</i>, not <i>your camera 738 * setup</i>. Do not use these camera properties for any non-sim vision calculations, especially 739 * the calibration data. Always use your camera's calibration data to do vision calculations in 740 * non-sim environments. These properties exist as a sample that may be used to get representative 741 * data in sim. 742 * 743 * @return The properties for this camera setup 744 */ 745 public static SimCameraProperties PI4_LIFECAM_640_480() { 746 var prop = new SimCameraProperties(); 747 prop.setCalibration( 748 640, 749 480, 750 MatBuilder.fill( 751 Nat.N3(), 752 Nat.N3(), 753 // intrinsic 754 669.1428078983059, 755 0.0, 756 322.53377249329213, 757 0.0, 758 646.9843137061716, 759 241.26567383784163, 760 0.0, 761 0.0, 762 1.0), 763 VecBuilder.fill( // distort 764 0.12788470750464645, 765 -1.2350335805796528, 766 0.0024990767286192732, 767 -0.0026958287600230705, 768 2.2951386729115537, 769 0, 770 0, 771 0)); 772 prop.setCalibError(0.26, 0.046); 773 prop.setFPS(15); 774 prop.setAvgLatencyMs(65); 775 prop.setLatencyStdDevMs(15); 776 return prop; 777 } 778 779 /** 780 * Creates a set of camera properties matching those of a Limelight 2 running at 640x480 781 * resolution. 782 * 783 * <p>Note that this set of properties represents <i>a camera setup</i>, not <i>your camera 784 * setup</i>. Do not use these camera properties for any non-sim vision calculations, especially 785 * the calibration data. Always use your camera's calibration data to do vision calculations in 786 * non-sim environments. These properties exist as a sample that may be used to get representative 787 * data in sim. 788 * 789 * @return The properties for this camera setup 790 */ 791 public static SimCameraProperties LL2_640_480() { 792 var prop = new SimCameraProperties(); 793 prop.setCalibration( 794 640, 795 480, 796 MatBuilder.fill( 797 Nat.N3(), 798 Nat.N3(), // intrinsic 799 511.22843367007755, 800 0.0, 801 323.62049380211096, 802 0.0, 803 514.5452336723849, 804 261.8827920543568, 805 0.0, 806 0.0, 807 1.0), 808 VecBuilder.fill( // distort 809 0.1917469998873756, 810 -0.5142936883324216, 811 0.012461562046896614, 812 0.0014084973492408186, 813 0.35160648971214437, 814 0, 815 0, 816 0)); 817 prop.setCalibError(0.25, 0.05); 818 prop.setFPS(15); 819 prop.setAvgLatencyMs(35); 820 prop.setLatencyStdDevMs(8); 821 return prop; 822 } 823 824 /** 825 * Creates a set of camera properties matching those of a Limelight 2 running at 960x720 826 * resolution. 827 * 828 * <p>Note that this set of properties represents <i>a camera setup</i>, not <i>your camera 829 * setup</i>. Do not use these camera properties for any non-sim vision calculations, especially 830 * the calibration data. Always use your camera's calibration data to do vision calculations in 831 * non-sim environments. These properties exist as a sample that may be used to get representative 832 * data in sim. 833 * 834 * @return The properties for this camera setup 835 */ 836 public static SimCameraProperties LL2_960_720() { 837 var prop = new SimCameraProperties(); 838 prop.setCalibration( 839 960, 840 720, 841 MatBuilder.fill( 842 Nat.N3(), 843 Nat.N3(), 844 // intrinsic 845 769.6873145148892, 846 0.0, 847 486.1096609458122, 848 0.0, 849 773.8164483705323, 850 384.66071662358354, 851 0.0, 852 0.0, 853 1.0), 854 VecBuilder.fill( // distort 855 0.189462064814501, 856 -0.49903003669627627, 857 0.007468423590519429, 858 0.002496885298683693, 859 0.3443122090208624, 860 0, 861 0, 862 0)); 863 prop.setCalibError(0.35, 0.10); 864 prop.setFPS(10); 865 prop.setAvgLatencyMs(50); 866 prop.setLatencyStdDevMs(15); 867 return prop; 868 } 869 870 /** 871 * Creates a set of camera properties matching those of a Limelight 2 running at 1280x720 872 * resolution. 873 * 874 * <p>Note that this set of properties represents <i>a camera setup</i>, not <i>your camera 875 * setup</i>. Do not use these camera properties for any non-sim vision calculations, especially 876 * the calibration data. Always use your camera's calibration data to do vision calculations in 877 * non-sim environments. These properties exist as a sample that may be used to get representative 878 * data in sim. 879 * 880 * @return The properties for this camera setup 881 */ 882 public static SimCameraProperties LL2_1280_720() { 883 var prop = new SimCameraProperties(); 884 prop.setCalibration( 885 1280, 886 720, 887 MatBuilder.fill( 888 Nat.N3(), 889 Nat.N3(), 890 // intrinsic 891 1011.3749416937393, 892 0.0, 893 645.4955139388737, 894 0.0, 895 1008.5391755084075, 896 508.32877656020196, 897 0.0, 898 0.0, 899 1.0), 900 VecBuilder.fill( // distort 901 0.13730101577061535, 902 -0.2904345656989261, 903 8.32475714507539E-4, 904 -3.694397782014239E-4, 905 0.09487962227027584, 906 0, 907 0, 908 0)); 909 prop.setCalibError(0.37, 0.06); 910 prop.setFPS(7); 911 prop.setAvgLatencyMs(60); 912 prop.setLatencyStdDevMs(20); 913 return prop; 914 } 915}