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 com.fasterxml.jackson.databind.ObjectMapper; 028import edu.wpi.first.math.MatBuilder; 029import edu.wpi.first.math.MathUtil; 030import edu.wpi.first.math.Matrix; 031import edu.wpi.first.math.Nat; 032import edu.wpi.first.math.Pair; 033import edu.wpi.first.math.VecBuilder; 034import edu.wpi.first.math.Vector; 035import edu.wpi.first.math.geometry.Pose3d; 036import edu.wpi.first.math.geometry.Rotation2d; 037import edu.wpi.first.math.geometry.Rotation3d; 038import edu.wpi.first.math.geometry.Translation3d; 039import edu.wpi.first.math.numbers.*; 040import edu.wpi.first.wpilibj.DriverStation; 041import java.io.IOException; 042import java.nio.file.Path; 043import java.util.ArrayList; 044import java.util.Arrays; 045import java.util.List; 046import java.util.Random; 047import org.ejml.data.DMatrix3; 048import org.ejml.dense.fixed.CommonOps_DDF3; 049import org.opencv.core.MatOfPoint2f; 050import org.opencv.core.Point; 051import org.opencv.imgproc.Imgproc; 052import org.photonvision.estimation.OpenCVHelp; 053import org.photonvision.estimation.RotTrlTransform3d; 054 055/** 056 * Calibration and performance values for this camera. 057 * 058 * <p>The resolution will affect the accuracy of projected(3d to 2d) target corners and similarly 059 * the severity of image noise on estimation(2d to 3d). 060 * 061 * <p>The camera intrinsics and distortion coefficients describe the results of calibration, and how 062 * to map between 3d field points and 2d image points. 063 * 064 * <p>The performance values (framerate/exposure time, latency) determine how often results should 065 * be updated and with how much latency in simulation. High exposure time causes motion blur which 066 * can inhibit target detection while moving. Note that latency estimation does not account for 067 * network latency and the latency reported will always be perfect. 068 */ 069public class SimCameraProperties { 070 private final Random rand = new Random(); 071 // calibration 072 private int resWidth; 073 private int resHeight; 074 private Matrix<N3, N3> camIntrinsics; 075 private Matrix<N8, N1> distCoeffs; 076 private double avgErrorPx; 077 private double errorStdDevPx; 078 // performance 079 private double frameSpeedMs = 0; 080 private double exposureTimeMs = 0; 081 private double avgLatencyMs = 0; 082 private double latencyStdDevMs = 0; 083 // util 084 private final List<DMatrix3> viewplanes = new ArrayList<>(); 085 086 /** Default constructor which is the same as {@link #PERFECT_90DEG} */ 087 public SimCameraProperties() { 088 setCalibration(960, 720, Rotation2d.fromDegrees(90)); 089 } 090 091 /** 092 * Reads camera properties from a photonvision <code>config.json</code> file. This is only the 093 * resolution, camera intrinsics, distortion coefficients, and average/std. dev. pixel error. 094 * Other camera properties must be set. 095 * 096 * @param path Path to the <code>config.json</code> file 097 * @param width The width of the desired resolution in the JSON 098 * @param height The height of the desired resolution in the JSON 099 * @throws IOException If reading the JSON fails, either from an invalid path or a missing/invalid 100 * calibrated resolution. 101 */ 102 public SimCameraProperties(String path, int width, int height) throws IOException { 103 this(Path.of(path), width, height); 104 } 105 106 /** 107 * Reads camera properties from a photonvision <code>config.json</code> file. This is only the 108 * resolution, camera intrinsics, distortion coefficients, and average/std. dev. pixel error. 109 * Other camera properties must be set. 110 * 111 * @param path Path to the <code>config.json</code> file 112 * @param width The width of the desired resolution in the JSON 113 * @param height The height of the desired resolution in the JSON 114 * @throws IOException If reading the JSON fails, either from an invalid path or a missing/invalid 115 * calibrated resolution. 116 */ 117 public SimCameraProperties(Path path, int width, int height) throws IOException { 118 var mapper = new ObjectMapper(); 119 var json = mapper.readTree(path.toFile()); 120 json = json.get("calibrations"); 121 boolean success = false; 122 try { 123 for (int i = 0; i < json.size() && !success; i++) { 124 // check if this calibration entry is our desired resolution 125 var calib = json.get(i); 126 int jsonWidth = calib.get("resolution").get("width").asInt(); 127 int jsonHeight = calib.get("resolution").get("height").asInt(); 128 if (jsonWidth != width || jsonHeight != height) continue; 129 // get the relevant calibration values 130 var jsonIntrinsicsNode = calib.get("cameraIntrinsics").get("data"); 131 double[] jsonIntrinsics = new double[jsonIntrinsicsNode.size()]; 132 for (int j = 0; j < jsonIntrinsicsNode.size(); j++) { 133 jsonIntrinsics[j] = jsonIntrinsicsNode.get(j).asDouble(); 134 } 135 var jsonDistortNode = calib.get("distCoeffs").get("data"); 136 double[] jsonDistortion = new double[8]; 137 Arrays.fill(jsonDistortion, 0); 138 for (int j = 0; j < jsonDistortNode.size(); j++) { 139 jsonDistortion[j] = jsonDistortNode.get(j).asDouble(); 140 } 141 var jsonViewErrors = calib.get("perViewErrors"); 142 double jsonAvgError = 0; 143 for (int j = 0; j < jsonViewErrors.size(); j++) { 144 jsonAvgError += jsonViewErrors.get(j).asDouble(); 145 } 146 jsonAvgError /= jsonViewErrors.size(); 147 double jsonErrorStdDev = calib.get("standardDeviation").asDouble(); 148 // assign the read JSON values to this CameraProperties 149 setCalibration( 150 jsonWidth, 151 jsonHeight, 152 MatBuilder.fill(Nat.N3(), Nat.N3(), jsonIntrinsics), 153 MatBuilder.fill(Nat.N8(), Nat.N1(), jsonDistortion)); 154 setCalibError(jsonAvgError, jsonErrorStdDev); 155 success = true; 156 } 157 } catch (Exception e) { 158 throw new IOException("Invalid calibration JSON"); 159 } 160 if (!success) throw new IOException("Requested resolution not found in calibration"); 161 } 162 163 public SimCameraProperties setRandomSeed(long seed) { 164 rand.setSeed(seed); 165 return this; 166 } 167 168 public SimCameraProperties setCalibration(int resWidth, int resHeight, Rotation2d fovDiag) { 169 if (fovDiag.getDegrees() < 1 || fovDiag.getDegrees() > 179) { 170 fovDiag = Rotation2d.fromDegrees(MathUtil.clamp(fovDiag.getDegrees(), 1, 179)); 171 DriverStation.reportError( 172 "Requested invalid FOV! Clamping between (1, 179) degrees...", false); 173 } 174 double resDiag = Math.sqrt(resWidth * resWidth + resHeight * resHeight); 175 double diagRatio = Math.tan(fovDiag.getRadians() / 2); 176 var fovWidth = new Rotation2d(Math.atan(diagRatio * (resWidth / resDiag)) * 2); 177 var fovHeight = new Rotation2d(Math.atan(diagRatio * (resHeight / resDiag)) * 2); 178 179 // assume no distortion 180 var distCoeff = VecBuilder.fill(0, 0, 0, 0, 0, 0, 0, 0); 181 182 // assume centered principal point (pixels) 183 double cx = resWidth / 2.0 - 0.5; 184 double cy = resHeight / 2.0 - 0.5; 185 186 // use given fov to determine focal point (pixels) 187 double fx = cx / Math.tan(fovWidth.getRadians() / 2.0); 188 double fy = cy / Math.tan(fovHeight.getRadians() / 2.0); 189 190 // create camera intrinsics matrix 191 var camIntrinsics = MatBuilder.fill(Nat.N3(), Nat.N3(), fx, 0, cx, 0, fy, cy, 0, 0, 1); 192 setCalibration(resWidth, resHeight, camIntrinsics, distCoeff); 193 194 return this; 195 } 196 197 public SimCameraProperties setCalibration( 198 int resWidth, int resHeight, Matrix<N3, N3> camIntrinsics, Matrix<N8, N1> distCoeffs) { 199 this.resWidth = resWidth; 200 this.resHeight = resHeight; 201 this.camIntrinsics = camIntrinsics; 202 this.distCoeffs = distCoeffs; 203 204 // left, right, up, and down view planes 205 var p = 206 new Translation3d[] { 207 new Translation3d( 208 1, 209 new Rotation3d(0, 0, getPixelYaw(0).plus(new Rotation2d(-Math.PI / 2)).getRadians())), 210 new Translation3d( 211 1, 212 new Rotation3d( 213 0, 0, getPixelYaw(resWidth).plus(new Rotation2d(Math.PI / 2)).getRadians())), 214 new Translation3d( 215 1, 216 new Rotation3d( 217 0, getPixelPitch(0).plus(new Rotation2d(Math.PI / 2)).getRadians(), 0)), 218 new Translation3d( 219 1, 220 new Rotation3d( 221 0, getPixelPitch(resHeight).plus(new Rotation2d(-Math.PI / 2)).getRadians(), 0)) 222 }; 223 viewplanes.clear(); 224 for (Translation3d translation3d : p) { 225 viewplanes.add( 226 new DMatrix3(translation3d.getX(), translation3d.getY(), translation3d.getZ())); 227 } 228 229 return this; 230 } 231 232 public SimCameraProperties setCalibError(double avgErrorPx, double errorStdDevPx) { 233 this.avgErrorPx = avgErrorPx; 234 this.errorStdDevPx = errorStdDevPx; 235 return this; 236 } 237 238 /** 239 * @param fps The average frames per second the camera should process at. <b>Exposure time limits 240 * FPS if set!</b> 241 */ 242 public SimCameraProperties setFPS(double fps) { 243 frameSpeedMs = Math.max(1000.0 / fps, exposureTimeMs); 244 245 return this; 246 } 247 248 /** 249 * @param exposureTimeMs The amount of time the "shutter" is open for one frame. Affects motion 250 * blur. <b>Frame speed(from FPS) is limited to this!</b> 251 */ 252 public SimCameraProperties setExposureTimeMs(double exposureTimeMs) { 253 this.exposureTimeMs = exposureTimeMs; 254 frameSpeedMs = Math.max(frameSpeedMs, exposureTimeMs); 255 256 return this; 257 } 258 259 /** 260 * @param avgLatencyMs The average latency (from image capture to data published) in milliseconds 261 * a frame should have 262 */ 263 public SimCameraProperties setAvgLatencyMs(double avgLatencyMs) { 264 this.avgLatencyMs = avgLatencyMs; 265 266 return this; 267 } 268 269 /** 270 * @param latencyStdDevMs The standard deviation in milliseconds of the latency 271 */ 272 public SimCameraProperties setLatencyStdDevMs(double latencyStdDevMs) { 273 this.latencyStdDevMs = latencyStdDevMs; 274 275 return this; 276 } 277 278 public int getResWidth() { 279 return resWidth; 280 } 281 282 public int getResHeight() { 283 return resHeight; 284 } 285 286 public int getResArea() { 287 return resWidth * resHeight; 288 } 289 290 /** Width:height */ 291 public double getAspectRatio() { 292 return (double) resWidth / resHeight; 293 } 294 295 public Matrix<N3, N3> getIntrinsics() { 296 return camIntrinsics.copy(); 297 } 298 299 public Vector<N8> getDistCoeffs() { 300 return new Vector<>(distCoeffs); 301 } 302 303 public double getFPS() { 304 return 1000.0 / frameSpeedMs; 305 } 306 307 public double getFrameSpeedMs() { 308 return frameSpeedMs; 309 } 310 311 public double getExposureTimeMs() { 312 return exposureTimeMs; 313 } 314 315 public double getAvgLatencyMs() { 316 return avgLatencyMs; 317 } 318 319 public double getLatencyStdDevMs() { 320 return latencyStdDevMs; 321 } 322 323 public SimCameraProperties copy() { 324 var newProp = new SimCameraProperties(); 325 newProp.setCalibration(resWidth, resHeight, camIntrinsics, distCoeffs); 326 newProp.setCalibError(avgErrorPx, errorStdDevPx); 327 newProp.setFPS(getFPS()); 328 newProp.setExposureTimeMs(exposureTimeMs); 329 newProp.setAvgLatencyMs(avgLatencyMs); 330 newProp.setLatencyStdDevMs(latencyStdDevMs); 331 return newProp; 332 } 333 334 /** 335 * The percentage(0 - 100) of this camera's resolution the contour takes up in pixels of the 336 * image. 337 * 338 * @param points Points of the contour 339 */ 340 public double getContourAreaPercent(Point[] points) { 341 return Imgproc.contourArea(new MatOfPoint2f(OpenCVHelp.getConvexHull(points))) 342 / getResArea() 343 * 100; 344 } 345 346 /** The yaw from the principal point of this camera to the pixel x value. Positive values left. */ 347 public Rotation2d getPixelYaw(double pixelX) { 348 double fx = camIntrinsics.get(0, 0); 349 // account for principal point not being centered 350 double cx = camIntrinsics.get(0, 2); 351 double xOffset = cx - pixelX; 352 return new Rotation2d(fx, xOffset); 353 } 354 355 /** 356 * The pitch from the principal point of this camera to the pixel y value. Pitch is positive down. 357 * 358 * <p>Note that this angle is naively computed and may be incorrect. See {@link 359 * #getCorrectedPixelRot(Point)}. 360 */ 361 public Rotation2d getPixelPitch(double pixelY) { 362 double fy = camIntrinsics.get(1, 1); 363 // account for principal point not being centered 364 double cy = camIntrinsics.get(1, 2); 365 double yOffset = cy - pixelY; 366 return new Rotation2d(fy, -yOffset); 367 } 368 369 /** 370 * Finds the yaw and pitch to the given image point. Yaw is positive left, and pitch is positive 371 * down. 372 * 373 * <p>Note that pitch is naively computed and may be incorrect. See {@link 374 * #getCorrectedPixelRot(Point)}. 375 */ 376 public Rotation3d getPixelRot(Point point) { 377 return new Rotation3d( 378 0, getPixelPitch(point.y).getRadians(), getPixelYaw(point.x).getRadians()); 379 } 380 381 /** 382 * Gives the yaw and pitch of the line intersecting the camera lens and the given pixel 383 * coordinates on the sensor. Yaw is positive left, and pitch positive down. 384 * 385 * <p>The pitch traditionally calculated from pixel offsets do not correctly account for non-zero 386 * values of yaw because of perspective distortion (not to be confused with lens distortion)-- for 387 * example, the pitch angle is naively calculated as: 388 * 389 * <pre>pitch = arctan(pixel y offset / focal length y)</pre> 390 * 391 * However, using focal length as a side of the associated right triangle is not correct when the 392 * pixel x value is not 0, because the distance from this pixel (projected on the x-axis) to the 393 * camera lens increases. Projecting a line back out of the camera with these naive angles will 394 * not intersect the 3d point that was originally projected into this 2d pixel. Instead, this 395 * length should be: 396 * 397 * <pre>focal length y ⟶ (focal length y / cos(arctan(pixel x offset / focal length x)))</pre> 398 * 399 * @return Rotation3d with yaw and pitch of the line projected out of the camera from the given 400 * pixel (roll is zero). 401 */ 402 public Rotation3d getCorrectedPixelRot(Point point) { 403 double fx = camIntrinsics.get(0, 0); 404 double cx = camIntrinsics.get(0, 2); 405 double xOffset = cx - point.x; 406 407 double fy = camIntrinsics.get(1, 1); 408 double cy = camIntrinsics.get(1, 2); 409 double yOffset = cy - point.y; 410 411 // calculate yaw normally 412 var yaw = new Rotation2d(fx, xOffset); 413 // correct pitch based on yaw 414 var pitch = new Rotation2d(fy / Math.cos(Math.atan(xOffset / fx)), -yOffset); 415 416 return new Rotation3d(0, pitch.getRadians(), yaw.getRadians()); 417 } 418 419 public Rotation2d getHorizFOV() { 420 // sum of FOV left and right principal point 421 var left = getPixelYaw(0); 422 var right = getPixelYaw(resWidth); 423 return left.minus(right); 424 } 425 426 public Rotation2d getVertFOV() { 427 // sum of FOV above and below principal point 428 var above = getPixelPitch(0); 429 var below = getPixelPitch(resHeight); 430 return below.minus(above); 431 } 432 433 public Rotation2d getDiagFOV() { 434 return new Rotation2d(Math.hypot(getHorizFOV().getRadians(), getVertFOV().getRadians())); 435 } 436 437 /** 438 * Determines where the line segment defined by the two given translations intersects the camera's 439 * frustum/field-of-vision, if at all. 440 * 441 * <p>The line is parametrized so any of its points <code>p = t * (b - a) + a</code>. This method 442 * returns these values of t, minimum first, defining the region of the line segment which is 443 * visible in the frustum. If both ends of the line segment are visible, this simply returns {0, 444 * 1}. If, for example, point b is visible while a is not, and half of the line segment is inside 445 * the camera frustum, {0.5, 1} would be returned. 446 * 447 * @param camRt The change in basis from world coordinates to camera coordinates. See {@link 448 * RotTrlTransform3d#makeRelativeTo(Pose3d)}. 449 * @param a The initial translation of the line 450 * @param b The final translation of the line 451 * @return A Pair of Doubles. The values may be null: 452 * <ul> 453 * <li>{Double, Double} : Two parametrized values(t), minimum first, representing which 454 * segment of the line is visible in the camera frustum. 455 * <li>{Double, null} : One value(t) representing a single intersection point. For example, 456 * the line only intersects the intersection of two adjacent viewplanes. 457 * <li>{null, null} : No values. The line segment is not visible in the camera frustum. 458 * </ul> 459 */ 460 public Pair<Double, Double> getVisibleLine( 461 RotTrlTransform3d camRt, Translation3d a, Translation3d b) { 462 // translations relative to the camera 463 var rela = camRt.apply(a); 464 var relb = camRt.apply(b); 465 466 // check if both ends are behind camera 467 if (rela.getX() <= 0 && relb.getX() <= 0) return new Pair<>(null, null); 468 469 var av = new DMatrix3(rela.getX(), rela.getY(), rela.getZ()); 470 var bv = new DMatrix3(relb.getX(), relb.getY(), relb.getZ()); 471 // a to b 472 var abv = new DMatrix3(); 473 CommonOps_DDF3.subtract(bv, av, abv); 474 475 // check if the ends of the line segment are visible 476 boolean aVisible = true; 477 boolean bVisible = true; 478 for (DMatrix3 normal : viewplanes) { 479 double aVisibility = CommonOps_DDF3.dot(av, normal); 480 if (aVisibility < 0) aVisible = false; 481 double bVisibility = CommonOps_DDF3.dot(bv, normal); 482 if (bVisibility < 0) bVisible = false; 483 // both ends are outside at least one of the same viewplane 484 if (aVisibility <= 0 && bVisibility <= 0) return new Pair<>(null, null); 485 } 486 // both ends are inside frustum 487 if (aVisible && bVisible) return new Pair<>((double) 0, 1.0); 488 489 // parametrized (t=0 at a, t=1 at b) intersections with viewplanes 490 double[] intersections = {Double.NaN, Double.NaN, Double.NaN, Double.NaN}; 491 // intersection points 492 List<DMatrix3> ipts = new ArrayList<>(); 493 for (double val : intersections) ipts.add(null); 494 495 // find intersections 496 for (int i = 0; i < viewplanes.size(); i++) { 497 var normal = viewplanes.get(i); 498 499 // we want to know the value of t when the line intercepts this plane 500 // parametrized: v = t * ab + a, where v lies on the plane 501 // we can find the projection of a onto the plane normal 502 // a_projn = normal.times(av.dot(normal) / normal.dot(normal)); 503 var a_projn = new DMatrix3(); 504 CommonOps_DDF3.scale( 505 CommonOps_DDF3.dot(av, normal) / CommonOps_DDF3.dot(normal, normal), normal, a_projn); 506 // this projection lets us determine the scalar multiple t of ab where 507 // (t * ab + a) is a vector which lies on the plane 508 if (Math.abs(CommonOps_DDF3.dot(abv, a_projn)) < 1e-5) continue; // line is parallel to plane 509 intersections[i] = CommonOps_DDF3.dot(a_projn, a_projn) / -CommonOps_DDF3.dot(abv, a_projn); 510 511 // vector a to the viewplane 512 var apv = new DMatrix3(); 513 CommonOps_DDF3.scale(intersections[i], abv, apv); 514 // av + apv = intersection point 515 var intersectpt = new DMatrix3(); 516 CommonOps_DDF3.add(av, apv, intersectpt); 517 ipts.set(i, intersectpt); 518 519 // discard intersections outside the camera frustum 520 for (int j = 1; j < viewplanes.size(); j++) { 521 int oi = (i + j) % viewplanes.size(); 522 var onormal = viewplanes.get(oi); 523 // if the dot of the intersection point with any plane normal is negative, it is outside 524 if (CommonOps_DDF3.dot(intersectpt, onormal) < 0) { 525 intersections[i] = Double.NaN; 526 ipts.set(i, null); 527 break; 528 } 529 } 530 531 // discard duplicate intersections 532 if (ipts.get(i) == null) continue; 533 for (int j = i - 1; j >= 0; j--) { 534 var oipt = ipts.get(j); 535 if (oipt == null) continue; 536 var diff = new DMatrix3(); 537 CommonOps_DDF3.subtract(oipt, intersectpt, diff); 538 if (CommonOps_DDF3.elementMaxAbs(diff) < 1e-4) { 539 intersections[i] = Double.NaN; 540 ipts.set(i, null); 541 break; 542 } 543 } 544 } 545 546 // determine visible segment (minimum and maximum t) 547 double inter1 = Double.NaN; 548 double inter2 = Double.NaN; 549 for (double inter : intersections) { 550 if (!Double.isNaN(inter)) { 551 if (Double.isNaN(inter1)) inter1 = inter; 552 else inter2 = inter; 553 } 554 } 555 556 // two viewplane intersections 557 if (!Double.isNaN(inter2)) { 558 double max = Math.max(inter1, inter2); 559 double min = Math.min(inter1, inter2); 560 if (aVisible) min = 0; 561 if (bVisible) max = 1; 562 return new Pair<>(min, max); 563 } 564 // one viewplane intersection 565 else if (!Double.isNaN(inter1)) { 566 if (aVisible) return new Pair<>((double) 0, inter1); 567 if (bVisible) return new Pair<>(inter1, 1.0); 568 return new Pair<>(inter1, null); 569 } 570 // no intersections 571 else return new Pair<>(null, null); 572 } 573 574 /** Returns these points after applying this camera's estimated noise. */ 575 public Point[] estPixelNoise(Point[] points) { 576 if (avgErrorPx == 0 && errorStdDevPx == 0) return points; 577 578 Point[] noisyPts = new Point[points.length]; 579 for (int i = 0; i < points.length; i++) { 580 var p = points[i]; 581 // error pixels in random direction 582 double error = avgErrorPx + rand.nextGaussian() * errorStdDevPx; 583 double errorAngle = rand.nextDouble() * 2 * Math.PI - Math.PI; 584 noisyPts[i] = 585 new Point(p.x + error * Math.cos(errorAngle), p.y + error * Math.sin(errorAngle)); 586 } 587 return noisyPts; 588 } 589 590 /** 591 * @return Noisy estimation of a frame's processing latency in milliseconds 592 */ 593 public double estLatencyMs() { 594 return Math.max(avgLatencyMs + rand.nextGaussian() * latencyStdDevMs, 0); 595 } 596 597 /** 598 * @return Estimate how long until the next frame should be processed in milliseconds 599 */ 600 public double estMsUntilNextFrame() { 601 // exceptional processing latency blocks the next frame 602 return frameSpeedMs + Math.max(0, estLatencyMs() - frameSpeedMs); 603 } 604 605 // pre-calibrated example cameras 606 607 /** 960x720 resolution, 90 degree FOV, "perfect" lagless camera */ 608 public static SimCameraProperties PERFECT_90DEG() { 609 return new SimCameraProperties(); 610 } 611 612 public static SimCameraProperties PI4_LIFECAM_320_240() { 613 var prop = new SimCameraProperties(); 614 prop.setCalibration( 615 320, 616 240, 617 MatBuilder.fill( 618 Nat.N3(), 619 Nat.N3(), 620 // intrinsic 621 328.2733242048587, 622 0.0, 623 164.8190261141906, 624 0.0, 625 318.0609794305216, 626 123.8633838438093, 627 0.0, 628 0.0, 629 1.0), 630 VecBuilder.fill( // distort 631 0.09957946553445934, 632 -0.9166265114485799, 633 0.0019519890627236526, 634 -0.0036071725380870333, 635 1.5627234622420942, 636 0, 637 0, 638 0)); 639 prop.setCalibError(0.21, 0.0124); 640 prop.setFPS(30); 641 prop.setAvgLatencyMs(30); 642 prop.setLatencyStdDevMs(10); 643 return prop; 644 } 645 646 public static SimCameraProperties PI4_LIFECAM_640_480() { 647 var prop = new SimCameraProperties(); 648 prop.setCalibration( 649 640, 650 480, 651 MatBuilder.fill( 652 Nat.N3(), 653 Nat.N3(), 654 // intrinsic 655 669.1428078983059, 656 0.0, 657 322.53377249329213, 658 0.0, 659 646.9843137061716, 660 241.26567383784163, 661 0.0, 662 0.0, 663 1.0), 664 VecBuilder.fill( // distort 665 0.12788470750464645, 666 -1.2350335805796528, 667 0.0024990767286192732, 668 -0.0026958287600230705, 669 2.2951386729115537, 670 0, 671 0, 672 0)); 673 prop.setCalibError(0.26, 0.046); 674 prop.setFPS(15); 675 prop.setAvgLatencyMs(65); 676 prop.setLatencyStdDevMs(15); 677 return prop; 678 } 679 680 public static SimCameraProperties LL2_640_480() { 681 var prop = new SimCameraProperties(); 682 prop.setCalibration( 683 640, 684 480, 685 MatBuilder.fill( 686 Nat.N3(), 687 Nat.N3(), // intrinsic 688 511.22843367007755, 689 0.0, 690 323.62049380211096, 691 0.0, 692 514.5452336723849, 693 261.8827920543568, 694 0.0, 695 0.0, 696 1.0), 697 VecBuilder.fill( // distort 698 0.1917469998873756, 699 -0.5142936883324216, 700 0.012461562046896614, 701 0.0014084973492408186, 702 0.35160648971214437, 703 0, 704 0, 705 0)); 706 prop.setCalibError(0.25, 0.05); 707 prop.setFPS(15); 708 prop.setAvgLatencyMs(35); 709 prop.setLatencyStdDevMs(8); 710 return prop; 711 } 712 713 public static SimCameraProperties LL2_960_720() { 714 var prop = new SimCameraProperties(); 715 prop.setCalibration( 716 960, 717 720, 718 MatBuilder.fill( 719 Nat.N3(), 720 Nat.N3(), 721 // intrinsic 722 769.6873145148892, 723 0.0, 724 486.1096609458122, 725 0.0, 726 773.8164483705323, 727 384.66071662358354, 728 0.0, 729 0.0, 730 1.0), 731 VecBuilder.fill( // distort 732 0.189462064814501, 733 -0.49903003669627627, 734 0.007468423590519429, 735 0.002496885298683693, 736 0.3443122090208624, 737 0, 738 0, 739 0)); 740 prop.setCalibError(0.35, 0.10); 741 prop.setFPS(10); 742 prop.setAvgLatencyMs(50); 743 prop.setLatencyStdDevMs(15); 744 return prop; 745 } 746 747 public static SimCameraProperties LL2_1280_720() { 748 var prop = new SimCameraProperties(); 749 prop.setCalibration( 750 1280, 751 720, 752 MatBuilder.fill( 753 Nat.N3(), 754 Nat.N3(), 755 // intrinsic 756 1011.3749416937393, 757 0.0, 758 645.4955139388737, 759 0.0, 760 1008.5391755084075, 761 508.32877656020196, 762 0.0, 763 0.0, 764 1.0), 765 VecBuilder.fill( // distort 766 0.13730101577061535, 767 -0.2904345656989261, 768 8.32475714507539E-4, 769 -3.694397782014239E-4, 770 0.09487962227027584, 771 0, 772 0, 773 0)); 774 prop.setCalibError(0.37, 0.06); 775 prop.setFPS(7); 776 prop.setAvgLatencyMs(60); 777 prop.setLatencyStdDevMs(20); 778 return prop; 779 } 780}