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 java.util.ArrayList; 028import java.util.List; 029import java.util.Optional; 030import java.util.stream.Collectors; 031import org.opencv.core.CvType; 032import org.opencv.core.Mat; 033import org.opencv.core.Point; 034import org.opencv.core.RotatedRect; 035import org.opencv.core.Scalar; 036import org.opencv.core.Size; 037import org.opencv.imgproc.Imgproc; 038import org.photonvision.PhotonCamera; 039import org.photonvision.PhotonTargetSortMode; 040import org.photonvision.common.networktables.NTTopicSet; 041import org.photonvision.estimation.CameraTargetRelation; 042import org.photonvision.estimation.OpenCVHelp; 043import org.photonvision.estimation.RotTrlTransform3d; 044import org.photonvision.estimation.TargetModel; 045import org.photonvision.estimation.VisionEstimation; 046import org.photonvision.targeting.MultiTargetPNPResult; 047import org.photonvision.targeting.PhotonPipelineResult; 048import org.photonvision.targeting.PhotonTrackedTarget; 049import org.photonvision.targeting.PnpResult; 050import org.wpilib.math.geometry.Pose3d; 051import org.wpilib.math.geometry.Transform3d; 052import org.wpilib.math.util.Pair; 053import org.wpilib.system.RobotController; 054import org.wpilib.util.PixelFormat; 055import org.wpilib.util.WPIUtilJNI; 056import org.wpilib.vision.apriltag.AprilTagFieldLayout; 057import org.wpilib.vision.apriltag.AprilTagFields; 058import org.wpilib.vision.camera.CvSource; 059import org.wpilib.vision.camera.OpenCvLoader; 060import org.wpilib.vision.camera.VideoSource.ConnectionStrategy; 061import org.wpilib.vision.stream.CameraServer; 062 063/** 064 * A handle for simulating {@link PhotonCamera} values. Processing simulated targets through this 065 * class will change the associated PhotonCamera's results. 066 */ 067@SuppressWarnings("unused") 068public class PhotonCameraSim implements AutoCloseable { 069 private final PhotonCamera cam; 070 071 @SuppressWarnings("doclint") 072 protected NTTopicSet ts = new NTTopicSet(); 073 074 private long heartbeatCounter = 1; 075 076 /** This simulated camera's {@link SimCameraProperties} */ 077 public final SimCameraProperties prop; 078 079 private long nextNTEntryTime = WPIUtilJNI.now(); 080 081 private double maxSightRangeMeters = Double.MAX_VALUE; 082 private static final double kDefaultMinAreaPx = 100; 083 private double minTargetAreaPercent; 084 private PhotonTargetSortMode sortMode = PhotonTargetSortMode.Largest; 085 086 private final AprilTagFieldLayout tagLayout; 087 088 // video stream simulation 089 private final CvSource videoSimRaw; 090 private final Mat videoSimFrameRaw = new Mat(); 091 private boolean videoSimRawEnabled = true; 092 private boolean videoSimWireframeEnabled = false; 093 private double videoSimWireframeResolution = 0.1; 094 private final CvSource videoSimProcessed; 095 private final Mat videoSimFrameProcessed = new Mat(); 096 private boolean videoSimProcEnabled = true; 097 098 static { 099 OpenCvLoader.forceStaticLoad(); 100 } 101 102 @Override 103 public void close() { 104 videoSimRaw.close(); 105 videoSimFrameRaw.release(); 106 videoSimProcessed.close(); 107 videoSimFrameProcessed.release(); 108 } 109 110 /** 111 * Constructs a handle for simulating {@link PhotonCamera} values. Processing simulated targets 112 * through this class will change the associated PhotonCamera's results. 113 * 114 * <p><b>This constructor's camera has a 90 deg FOV with no simulated lag!</b> 115 * 116 * <p>By default, the minimum target area is 100 pixels and there is no maximum sight range. 117 * 118 * @param camera The camera to be simulated 119 */ 120 public PhotonCameraSim(PhotonCamera camera) { 121 this(camera, SimCameraProperties.PERFECT_90DEG()); 122 } 123 124 /** 125 * Constructs a handle for simulating {@link PhotonCamera} values. Processing simulated targets 126 * through this class will change the associated PhotonCamera's results. 127 * 128 * <p>By default, the minimum target area is 100 pixels and there is no maximum sight range. 129 * 130 * @param camera The camera to be simulated 131 * @param prop Properties of this camera such as FOV and FPS 132 */ 133 public PhotonCameraSim(PhotonCamera camera, SimCameraProperties prop) { 134 this(camera, prop, AprilTagFieldLayout.loadField(AprilTagFields.kDefaultField)); 135 } 136 137 /** 138 * Constructs a handle for simulating {@link PhotonCamera} values. Processing simulated targets 139 * through this class will change the associated PhotonCamera's results. 140 * 141 * <p>By default, the minimum target area is 100 pixels and there is no maximum sight range. 142 * 143 * @param camera The camera to be simulated 144 * @param prop Properties of this camera such as FOV and FPS 145 * @param tagLayout The {@link AprilTagFieldLayout} used to solve for tag positions. 146 */ 147 public PhotonCameraSim( 148 PhotonCamera camera, SimCameraProperties prop, AprilTagFieldLayout tagLayout) { 149 this.cam = camera; 150 this.prop = prop; 151 this.tagLayout = tagLayout; 152 setMinTargetAreaPixels(kDefaultMinAreaPx); 153 154 videoSimRaw = 155 CameraServer.putVideo(camera.getName() + "-raw", prop.getResWidth(), prop.getResHeight()); 156 videoSimRaw.setPixelFormat(PixelFormat.GRAY); 157 videoSimProcessed = 158 CameraServer.putVideo( 159 camera.getName() + "-processed", prop.getResWidth(), prop.getResHeight()); 160 161 ts.removeEntries(); 162 ts.subTable = camera.getCameraTable(); 163 ts.updateEntries(); 164 } 165 166 /** 167 * Constructs a handle for simulating {@link PhotonCamera} values. Processing simulated targets 168 * through this class will change the associated PhotonCamera's results. 169 * 170 * @param camera The camera to be simulated 171 * @param prop Properties of this camera such as FOV and FPS 172 * @param minTargetAreaPercent The minimum percentage (0 - 100) a detected target must take up of 173 * the camera's image to be processed. Match this with your contour filtering settings in the 174 * PhotonVision GUI. 175 * @param maxSightRangeMeters Maximum distance at which the target is illuminated to your camera. 176 * Note that minimum target area of the image is separate from this. 177 */ 178 public PhotonCameraSim( 179 PhotonCamera camera, 180 SimCameraProperties prop, 181 double minTargetAreaPercent, 182 double maxSightRangeMeters) { 183 this(camera, prop, AprilTagFieldLayout.loadField(AprilTagFields.kDefaultField)); 184 this.minTargetAreaPercent = minTargetAreaPercent; 185 this.maxSightRangeMeters = maxSightRangeMeters; 186 } 187 188 /** 189 * Constructs a handle for simulating {@link PhotonCamera} values. Processing simulated targets 190 * through this class will change the associated PhotonCamera's results. 191 * 192 * @param camera The camera to be simulated 193 * @param prop Properties of this camera such as FOV and FPS 194 * @param minTargetAreaPercent The minimum percentage (0 - 100) a detected target must take up of 195 * the camera's image to be processed. Match this with your contour filtering settings in the 196 * PhotonVision GUI. 197 * @param maxSightRangeMeters Maximum distance at which the target is illuminated to your camera. 198 * Note that minimum target area of the image is separate from this. 199 * @param tagLayout AprilTag field layout to use for multi-tag estimation 200 */ 201 public PhotonCameraSim( 202 PhotonCamera camera, 203 SimCameraProperties prop, 204 double minTargetAreaPercent, 205 double maxSightRangeMeters, 206 AprilTagFieldLayout tagLayout) { 207 this(camera, prop); 208 this.minTargetAreaPercent = minTargetAreaPercent; 209 this.maxSightRangeMeters = maxSightRangeMeters; 210 } 211 212 /** 213 * Returns the camera being simulated. 214 * 215 * @return The camera 216 */ 217 public PhotonCamera getCamera() { 218 return cam; 219 } 220 221 /** 222 * Returns the minimum percentage (0 - 100) a detected target must take up of the camera's image 223 * to be processed. 224 * 225 * @return The percentage 226 */ 227 public double getMinTargetAreaPercent() { 228 return minTargetAreaPercent; 229 } 230 231 /** 232 * Returns the minimum number of pixels a detected target must take up in the camera's image to be 233 * processed. 234 * 235 * @return The number of pixels 236 */ 237 public double getMinTargetAreaPixels() { 238 return minTargetAreaPercent / 100.0 * prop.getResArea(); 239 } 240 241 /** 242 * Returns the maximum distance at which the target is illuminated to your camera. Note that 243 * minimum target area of the image is separate from this. 244 * 245 * @return The distance in meters 246 */ 247 public double getMaxSightRangeMeters() { 248 return maxSightRangeMeters; 249 } 250 251 /** 252 * Returns the order the targets are sorted in the pipeline result. 253 * 254 * @return The target sorting order 255 */ 256 public PhotonTargetSortMode getTargetSortMode() { 257 return sortMode; 258 } 259 260 public CvSource getVideoSimRaw() { 261 return videoSimRaw; 262 } 263 264 public Mat getVideoSimFrameRaw() { 265 return videoSimFrameRaw; 266 } 267 268 /** 269 * Determines if this target's pose should be visible to the camera without considering its 270 * projected image points. Does not account for image area. 271 * 272 * @param camPose Camera's 3d pose 273 * @param target Vision target containing pose and shape 274 * @return If this vision target can be seen before image projection. 275 */ 276 public boolean canSeeTargetPose(Pose3d camPose, VisionTargetSim target) { 277 var rel = new CameraTargetRelation(camPose, target.getPose()); 278 279 return ( 280 // target translation is outside of camera's FOV 281 (Math.abs(rel.camToTargYaw.getDegrees()) < prop.getHorizFOV().getDegrees() / 2) 282 && (Math.abs(rel.camToTargPitch.getDegrees()) < prop.getVertFOV().getDegrees() / 2) 283 && (!target.getModel().isPlanar 284 || Math.abs(rel.targToCamAngle.getDegrees()) 285 < 90) // camera is behind planar target and it should be occluded 286 && (rel.camToTarg.getTranslation().getNorm() <= maxSightRangeMeters)); // target is too far 287 } 288 289 /** 290 * Determines if all target points are inside the camera's image. 291 * 292 * @param points The target's 2d image points 293 * @return True if all the target points are inside the camera's image, false otherwise. 294 */ 295 public boolean canSeeCorners(Point[] points) { 296 for (var point : points) { 297 if (Math.clamp(point.x, 0, prop.getResWidth()) != point.x 298 || Math.clamp(point.y, 0, prop.getResHeight()) != point.y) { 299 return false; // point is outside of resolution 300 } 301 } 302 return true; 303 } 304 305 /** 306 * Determine if this camera should process a new frame based on performance metrics and the time 307 * since the last update. This returns an Optional which is either empty if no update should occur 308 * or a Long of the timestamp in microseconds of when the frame which should be received by NT. If 309 * a timestamp is returned, the last frame update time becomes that timestamp. 310 * 311 * @return Optional long which is empty while blocked or the NT entry timestamp in microseconds if 312 * ready 313 */ 314 public Optional<Long> consumeNextEntryTime() { 315 // check if this camera is ready for another frame update 316 long now = WPIUtilJNI.now(); 317 long timestamp = -1; 318 int iter = 0; 319 // prepare next latest update 320 while (now >= nextNTEntryTime) { 321 timestamp = nextNTEntryTime; 322 long frameTime = (long) (prop.estMsUntilNextFrame() * 1e3); 323 nextNTEntryTime += frameTime; 324 325 // if frame time is very small, avoid blocking 326 if (iter++ > 50) { 327 timestamp = now; 328 nextNTEntryTime = now + frameTime; 329 break; 330 } 331 } 332 // return the timestamp of the latest update 333 if (timestamp >= 0) return Optional.of(timestamp); 334 // or this camera isn't ready to process yet 335 else return Optional.empty(); 336 } 337 338 /** 339 * Sets the minimum percentage (0 - 100) a detected target must take up of the camera's image to 340 * be processed. 341 * 342 * @param areaPercent The percentage 343 */ 344 public void setMinTargetAreaPercent(double areaPercent) { 345 this.minTargetAreaPercent = areaPercent; 346 } 347 348 /** 349 * Sets the minimum number of pixels a detected target must take up in the camera's image to be 350 * processed. 351 * 352 * @param areaPx The number of pixels 353 */ 354 public void setMinTargetAreaPixels(double areaPx) { 355 this.minTargetAreaPercent = areaPx / prop.getResArea() * 100; 356 } 357 358 /** 359 * Sets the maximum distance at which the target is illuminated to your camera. Note that minimum 360 * target area of the image is separate from this. 361 * 362 * @param rangeMeters The distance in meters 363 */ 364 public void setMaxSightRange(double rangeMeters) { 365 this.maxSightRangeMeters = rangeMeters; 366 } 367 368 /** 369 * Defines the order the targets are sorted in the pipeline result. 370 * 371 * @param sortMode The target sorting order 372 */ 373 public void setTargetSortMode(PhotonTargetSortMode sortMode) { 374 if (sortMode != null) this.sortMode = sortMode; 375 } 376 377 /** 378 * Sets whether the raw video stream simulation is enabled. 379 * 380 * <p>Note: This may increase loop times. 381 * 382 * @param enabled Whether or not to enable the raw video stream 383 */ 384 public void enableRawStream(boolean enabled) { 385 videoSimRawEnabled = enabled; 386 } 387 388 /** 389 * Sets whether a wireframe of the field is drawn to the raw video stream. 390 * 391 * <p>Note: This will dramatically increase loop times. 392 * 393 * @param enabled Whether or not to enable the wireframe in the raw video stream 394 */ 395 public void enableDrawWireframe(boolean enabled) { 396 videoSimWireframeEnabled = enabled; 397 } 398 399 /** 400 * Sets the resolution of the drawn wireframe if enabled. Drawn line segments will be subdivided 401 * into smaller segments based on a threshold set by the resolution. 402 * 403 * @param resolution Resolution as a fraction(0 - 1) of the video frame's diagonal length in 404 * pixels 405 */ 406 public void setWireframeResolution(double resolution) { 407 videoSimWireframeResolution = resolution; 408 } 409 410 /** 411 * Sets whether the processed video stream simulation is enabled. 412 * 413 * @param enabled Whether or not to enable the processed video stream 414 */ 415 public void enableProcessedStream(boolean enabled) { 416 videoSimProcEnabled = enabled; 417 } 418 419 public PhotonPipelineResult process( 420 double latencyMillis, Pose3d cameraPose, List<VisionTargetSim> targets) { 421 // sort targets by distance to camera 422 targets = new ArrayList<>(targets); 423 targets.sort( 424 (t1, t2) -> { 425 double dist1 = t1.getPose().getTranslation().getDistance(cameraPose.getTranslation()); 426 double dist2 = t2.getPose().getTranslation().getDistance(cameraPose.getTranslation()); 427 if (dist1 == dist2) return 0; 428 return dist1 < dist2 ? 1 : -1; 429 }); 430 // all targets visible before noise 431 var visibleTgts = new ArrayList<Pair<VisionTargetSim, Point[]>>(); 432 // all targets actually detected by camera (after noise) 433 var detectableTgts = new ArrayList<PhotonTrackedTarget>(); 434 // basis change from world coordinates to camera coordinates 435 var camRt = RotTrlTransform3d.makeRelativeTo(cameraPose); 436 437 // reset our frame 438 VideoSimUtil.updateVideoProp(videoSimRaw, prop); 439 VideoSimUtil.updateVideoProp(videoSimProcessed, prop); 440 Size videoFrameSize = new Size(prop.getResWidth(), prop.getResHeight()); 441 Mat.zeros(videoFrameSize, CvType.CV_8UC1).assignTo(videoSimFrameRaw); 442 443 for (var tgt : targets) { 444 if (detectableTgts.size() >= 50) { 445 break; 446 } 447 448 // pose isn't visible, skip to next 449 if (!canSeeTargetPose(cameraPose, tgt)) continue; 450 451 // find target's 3d corner points 452 var fieldCorners = tgt.getFieldVertices(); 453 if (tgt.getModel().isSpherical) { // target is spherical 454 var model = tgt.getModel(); 455 // orient the model to the camera (like a sprite/decal) so it appears similar regardless of 456 // view 457 fieldCorners = 458 model.getFieldVertices( 459 TargetModel.getOrientedPose( 460 tgt.getPose().getTranslation(), cameraPose.getTranslation())); 461 } 462 // project 3d target points into 2d image points 463 var imagePoints = 464 OpenCVHelp.projectPoints(prop.getIntrinsics(), prop.getDistCoeffs(), camRt, fieldCorners); 465 // spherical targets need a rotated rectangle of their midpoints for visualization 466 if (tgt.getModel().isSpherical) { 467 var center = OpenCVHelp.avgPoint(imagePoints); 468 int l = 0, t, b, r = 0; 469 // reference point (left side midpoint) 470 for (int i = 1; i < 4; i++) { 471 if (imagePoints[i].x < imagePoints[l].x) l = i; 472 } 473 var lc = imagePoints[l]; 474 // determine top, right, bottom midpoints 475 double[] angles = new double[4]; 476 t = (l + 1) % 4; 477 b = (l + 1) % 4; 478 for (int i = 0; i < 4; i++) { 479 if (i == l) continue; 480 var ic = imagePoints[i]; 481 angles[i] = Math.atan2(lc.y - ic.y, ic.x - lc.x); 482 if (angles[i] >= angles[t]) t = i; 483 if (angles[i] <= angles[b]) b = i; 484 } 485 for (int i = 0; i < 4; i++) { 486 if (i != t && i != l && i != b) r = i; 487 } 488 // create RotatedRect from midpoints 489 var rect = 490 new RotatedRect( 491 new Point(center.x, center.y), 492 new Size(imagePoints[r].x - lc.x, imagePoints[b].y - imagePoints[t].y), 493 Math.toDegrees(-angles[r])); 494 // set target corners to rect corners 495 Point[] points = new Point[4]; 496 rect.points(points); 497 imagePoints = points; 498 } 499 // save visible targets for raw video stream simulation 500 visibleTgts.add(new Pair<>(tgt, imagePoints)); 501 // estimate pixel noise 502 var noisyTargetCorners = prop.estPixelNoise(imagePoints); 503 // find the minimum area rectangle of target corners 504 var minAreaRect = OpenCVHelp.getMinAreaRect(noisyTargetCorners); 505 Point[] minAreaRectPts = new Point[4]; 506 minAreaRect.points(minAreaRectPts); 507 // find the (naive) 2d yaw/pitch 508 var centerPt = minAreaRect.center; 509 var centerRot = prop.getPixelRot(centerPt); 510 // find contour area 511 double areaPercent = prop.getContourAreaPercent(noisyTargetCorners); 512 513 // projected target can't be detected, skip to next 514 if (!(canSeeCorners(noisyTargetCorners) && areaPercent >= minTargetAreaPercent)) continue; 515 516 var pnpSim = new PnpResult(); 517 if (tgt.fiducialID >= 0 && tgt.getFieldVertices().size() == 4) { // single AprilTag solvePNP 518 pnpSim = 519 OpenCVHelp.solvePNP_SQUARE( 520 prop.getIntrinsics(), 521 prop.getDistCoeffs(), 522 tgt.getModel().vertices, 523 noisyTargetCorners) 524 .get(); 525 } 526 527 // If object detection (user classId valid) but conf wasn't provided, estimate 528 int classId = tgt.objDetClassId; 529 float conf = tgt.objDetConf; 530 if (classId >= 0 && conf < 0) { 531 // Simulate confidence using sqrt-scaled area for a more realistic 532 // curve. Raw areaPercent/100 is tiny for most targets; sqrt scaling 533 // gives reasonable values even for small-but-visible objects. 534 conf = (float) Math.clamp(Math.sqrt(areaPercent / 100.0) * 2.0, 0.0, 1.0); 535 } 536 537 detectableTgts.add( 538 new PhotonTrackedTarget( 539 -Math.toDegrees(centerRot.getZ()), 540 -Math.toDegrees(centerRot.getY()), 541 areaPercent, 542 Math.toDegrees(centerRot.getX()), 543 tgt.fiducialID, 544 classId, 545 conf, 546 pnpSim.best, 547 pnpSim.alt, 548 pnpSim.ambiguity, 549 OpenCVHelp.pointsToCorners(minAreaRectPts), 550 OpenCVHelp.pointsToCorners(noisyTargetCorners))); 551 } 552 // render visible tags to raw video frame 553 if (videoSimRawEnabled) { 554 // draw field wireframe 555 if (videoSimWireframeEnabled) { 556 VideoSimUtil.drawFieldWireframe( 557 camRt, 558 prop, 559 videoSimWireframeResolution, 560 1.5, 561 new Scalar(80), 562 6, 563 1, 564 new Scalar(30), 565 videoSimFrameRaw); 566 } 567 568 // draw targets 569 for (var pair : visibleTgts) { 570 var tgt = pair.getFirst(); 571 var corn = pair.getSecond(); 572 573 if (tgt.fiducialID >= 0) { // apriltags 574 VideoSimUtil.warp36h11TagImage(tgt.fiducialID, corn, true, videoSimFrameRaw); 575 } else if (!tgt.getModel().isSpherical) { // non-spherical targets 576 var contour = corn; 577 if (!tgt.getModel() 578 .isPlanar) { // visualization cant handle non-convex projections of 3d models 579 contour = OpenCVHelp.getConvexHull(contour); 580 } 581 VideoSimUtil.drawPoly(contour, -1, new Scalar(255), true, videoSimFrameRaw); 582 } else { // spherical targets 583 VideoSimUtil.drawInscribedEllipse(corn, new Scalar(255), videoSimFrameRaw); 584 } 585 } 586 videoSimRaw.putFrame(videoSimFrameRaw); 587 } else videoSimRaw.setConnectionStrategy(ConnectionStrategy.kForceClose); 588 // draw/annotate target detection outline on processed view 589 if (videoSimProcEnabled) { 590 Imgproc.cvtColor(videoSimFrameRaw, videoSimFrameProcessed, Imgproc.COLOR_GRAY2BGR); 591 Imgproc.drawMarker( // crosshair 592 videoSimFrameProcessed, 593 new Point(prop.getResWidth() / 2.0, prop.getResHeight() / 2.0), 594 new Scalar(0, 255, 0), 595 Imgproc.MARKER_CROSS, 596 (int) VideoSimUtil.getScaledThickness(15, videoSimFrameProcessed), 597 (int) VideoSimUtil.getScaledThickness(1, videoSimFrameProcessed), 598 Imgproc.LINE_AA); 599 for (var tgt : detectableTgts) { 600 if (tgt.getFiducialId() >= 0) { // apriltags 601 VideoSimUtil.drawTagDetection( 602 tgt.getFiducialId(), 603 OpenCVHelp.cornersToPoints(tgt.getDetectedCorners()), 604 videoSimFrameProcessed); 605 } else { // other targets 606 // bounding rectangle 607 Imgproc.rectangle( 608 videoSimFrameProcessed, 609 OpenCVHelp.getBoundingRect(OpenCVHelp.cornersToPoints(tgt.getDetectedCorners())), 610 new Scalar(0, 0, 255), 611 (int) VideoSimUtil.getScaledThickness(1, videoSimFrameProcessed), 612 Imgproc.LINE_AA); 613 614 VideoSimUtil.drawPoly( 615 OpenCVHelp.cornersToPoints(tgt.getMinAreaRectCorners()), 616 (int) VideoSimUtil.getScaledThickness(1, videoSimFrameProcessed), 617 new Scalar(255, 30, 30), 618 true, 619 videoSimFrameProcessed); 620 } 621 } 622 videoSimProcessed.putFrame(videoSimFrameProcessed); 623 } else videoSimProcessed.setConnectionStrategy(ConnectionStrategy.kForceClose); 624 625 // calculate multitag results 626 Optional<MultiTargetPNPResult> multitagResult = Optional.empty(); 627 // TODO: Implement ATFL subscribing in backend 628 // var tagLayout = cam.getAprilTagFieldLayout(); 629 var visibleLayoutTags = VisionEstimation.getVisibleLayoutTags(detectableTgts, tagLayout); 630 if (visibleLayoutTags.size() > 1) { 631 List<Short> usedIDs = 632 visibleLayoutTags.stream().map(t -> (short) t.ID).sorted().collect(Collectors.toList()); 633 var pnpResult = 634 VisionEstimation.estimateCamPosePNP( 635 prop.getIntrinsics(), 636 prop.getDistCoeffs(), 637 detectableTgts, 638 tagLayout, 639 TargetModel.kAprilTag36h11); 640 641 if (pnpResult.isPresent()) { 642 multitagResult = Optional.of(new MultiTargetPNPResult(pnpResult.get(), usedIDs)); 643 } 644 } 645 646 // sort target order 647 if (sortMode != null) { 648 detectableTgts.sort(sortMode.getComparator()); 649 } 650 651 // put this simulated data to NT 652 var now = RobotController.getMonotonicTime(); 653 var ret = 654 new PhotonPipelineResult( 655 heartbeatCounter, 656 now - (long) (latencyMillis * 1000), 657 now, 658 // Pretend like we heard a pong recently 659 1000L + (long) ((Math.random() - 0.5) * 50), 660 detectableTgts, 661 multitagResult); 662 return ret; 663 } 664 665 /** 666 * Simulate one processed frame of vision data, putting one result to NT at current timestamp. 667 * Image capture time is assumed be (current time - latency). 668 * 669 * @param result The pipeline result to submit 670 */ 671 public void submitProcessedFrame(PhotonPipelineResult result) { 672 submitProcessedFrame(result, WPIUtilJNI.now()); 673 } 674 675 /** 676 * Simulate one processed frame of vision data, putting one result to NT. Image capture timestamp 677 * overrides {@link PhotonPipelineResult#getTimestampSeconds() getTimestampSeconds()} for more 678 * precise latency simulation. 679 * 680 * @param result The pipeline result to submit 681 * @param receiveTimestamp The (sim) timestamp when this result was read by NT in microseconds 682 */ 683 public void submitProcessedFrame(PhotonPipelineResult result, long receiveTimestamp) { 684 ts.latencyMillisEntry.set(result.metadata.getLatencyMillis(), receiveTimestamp); 685 686 // Results are now dynamically sized, so let's guess 1024 bytes is big enough 687 ts.resultPublisher.set(result, 1024); 688 689 boolean hasTargets = result.hasTargets(); 690 ts.hasTargetEntry.set(hasTargets, receiveTimestamp); 691 if (!hasTargets) { 692 ts.targetPitchEntry.set(0.0, receiveTimestamp); 693 ts.targetYawEntry.set(0.0, receiveTimestamp); 694 ts.targetAreaEntry.set(0.0, receiveTimestamp); 695 ts.targetPoseEntry.set(new Transform3d(), receiveTimestamp); 696 ts.targetSkewEntry.set(0.0, receiveTimestamp); 697 } else { 698 var bestTarget = result.getBestTarget(); 699 700 ts.targetPitchEntry.set(bestTarget.getPitch(), receiveTimestamp); 701 ts.targetYawEntry.set(bestTarget.getYaw(), receiveTimestamp); 702 ts.targetAreaEntry.set(bestTarget.getArea(), receiveTimestamp); 703 ts.targetSkewEntry.set(bestTarget.getSkew(), receiveTimestamp); 704 705 var transform = bestTarget.getBestCameraToTarget(); 706 ts.targetPoseEntry.set(transform, receiveTimestamp); 707 } 708 709 ts.cameraIntrinsicsPublisher.set(prop.getIntrinsics().getData(), receiveTimestamp); 710 ts.cameraDistortionPublisher.set(prop.getDistCoeffs().getData(), receiveTimestamp); 711 712 ts.heartbeatPublisher.set(heartbeatCounter, receiveTimestamp); 713 heartbeatCounter += 1; 714 } 715}