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 edu.wpi.first.apriltag.AprilTag; 028import edu.wpi.first.cscore.CvSource; 029import edu.wpi.first.cscore.OpenCvLoader; 030import edu.wpi.first.math.geometry.Pose3d; 031import edu.wpi.first.math.geometry.Translation3d; 032import edu.wpi.first.math.util.Units; 033import edu.wpi.first.util.RawFrame; 034import java.util.ArrayList; 035import java.util.Arrays; 036import java.util.HashMap; 037import java.util.List; 038import java.util.Map; 039import org.opencv.core.Core; 040import org.opencv.core.CvType; 041import org.opencv.core.Mat; 042import org.opencv.core.MatOfPoint; 043import org.opencv.core.MatOfPoint2f; 044import org.opencv.core.Point; 045import org.opencv.core.Rect; 046import org.opencv.core.Scalar; 047import org.opencv.core.Size; 048import org.opencv.imgproc.Imgproc; 049import org.photonvision.estimation.OpenCVHelp; 050import org.photonvision.estimation.RotTrlTransform3d; 051 052public class VideoSimUtil { 053 // Tag IDs start at 0, this should be set to 1 greater than the maximum tag ID required 054 public static final int kNumTags36h11 = 40; 055 056 // All 36h11 tag images 057 private static final Map<Integer, Mat> kTag36h11Images = new HashMap<>(); 058 // Points corresponding to marker(black square) corners of 10x10 36h11 tag images 059 public static final Point[] kTag36h11MarkerPts; 060 061 // field dimensions for wireframe 062 private static double fieldLength = 16.54175; 063 private static double fieldWidth = 8.0137; 064 065 static { 066 OpenCvLoader.forceStaticLoad(); 067 068 // create Mats of 10x10 apriltag images 069 for (int i = 0; i < VideoSimUtil.kNumTags36h11; i++) { 070 Mat tagImage = VideoSimUtil.get36h11TagImage(i); 071 kTag36h11Images.put(i, tagImage); 072 } 073 074 kTag36h11MarkerPts = get36h11MarkerPts(); 075 } 076 077 private VideoSimUtil() {} 078 079 /** Updates the properties of this CvSource video stream with the given camera properties. */ 080 public static void updateVideoProp(CvSource video, SimCameraProperties prop) { 081 video.setResolution(prop.getResWidth(), prop.getResHeight()); 082 video.setFPS((int) prop.getFPS()); 083 } 084 085 /** 086 * Gets the points representing the corners of this image. Because image pixels are accessed 087 * through a Mat, the point (0,0) actually represents the center of the top-left pixel and not the 088 * actual top-left corner. 089 * 090 * <p>Order of corners returned is: [BL, BR, TR, TL] 091 * 092 * @param size Size of image 093 * @return The corners 094 */ 095 public static Point[] getImageCorners(Size size) { 096 return new Point[] { 097 new Point(-0.5, size.height - 0.5), 098 new Point(size.width - 0.5, size.height - 0.5), 099 new Point(size.width - 0.5, -0.5), 100 new Point(-0.5, -0.5) 101 }; 102 } 103 104 /** 105 * Gets the 10x10 (grayscale) image of a specific 36h11 AprilTag. 106 * 107 * <p>WARNING: This creates a {@link RawFrame} instance but does not close it, which would result 108 * in a resource leak if the {@link Mat} is garbage-collected. Unfortunately, closing the {@code 109 * RawFrame} inside this function would delete the underlying data that backs the {@code 110 * ByteBuffer} that is passed to the {@code Mat} constructor (see comments on <a 111 * href="https://github.com/PhotonVision/photonvision/pull/2023">PR 2023</a> for details). 112 * Luckily, this method is private and is (as of Aug 2025) only used to populate the {@link 113 * #kTag36h11Images} static map at static-initialization time. 114 * 115 * @param id The fiducial id of the desired tag 116 */ 117 private static Mat get36h11TagImage(int id) { 118 RawFrame frame = AprilTag.generate36h11AprilTagImage(id); 119 return new Mat( 120 frame.getHeight(), frame.getWidth(), CvType.CV_8UC1, frame.getData(), frame.getStride()); 121 } 122 123 /** 124 * Gets the points representing the marker(black square) corners. 125 * 126 * @return The points 127 */ 128 public static Point[] get36h11MarkerPts() { 129 return get36h11MarkerPts(1); 130 } 131 132 /** 133 * Gets the points representing the marker(black square) corners. 134 * 135 * @param scale The scale of the tag image (10*scale x 10*scale image) 136 * @return The points 137 */ 138 public static Point[] get36h11MarkerPts(int scale) { 139 var roi36h11 = new Rect(new Point(1, 1), new Size(8, 8)); 140 roi36h11.x *= scale; 141 roi36h11.y *= scale; 142 roi36h11.width *= scale; 143 roi36h11.height *= scale; 144 var pts = getImageCorners(roi36h11.size()); 145 for (int i = 0; i < pts.length; i++) { 146 var pt = pts[i]; 147 pts[i] = new Point(roi36h11.tl().x + pt.x, roi36h11.tl().y + pt.y); 148 } 149 return pts; 150 } 151 152 /** 153 * Warps the image of a specific 36h11 AprilTag onto the destination image at the given points. 154 * 155 * @param tagId The id of the specific tag to warp onto the destination image 156 * @param dstPoints Points(4) in destination image where the tag marker(black square) corners 157 * should be warped onto. 158 * @param antialiasing If antialiasing should be performed by automatically 159 * supersampling/interpolating the warped image. This should be used if better stream quality 160 * is desired or target detection is being done on the stream, but can hurt performance. 161 * @param destination The destination image to place the warped tag image onto. 162 */ 163 public static void warp36h11TagImage( 164 int tagId, Point[] dstPoints, boolean antialiasing, Mat destination) { 165 Mat tagImage = kTag36h11Images.get(tagId); 166 if (tagImage == null || tagImage.empty()) return; 167 var tagPoints = new MatOfPoint2f(kTag36h11MarkerPts); 168 // points of tag image corners 169 var tagImageCorners = new MatOfPoint2f(getImageCorners(tagImage.size())); 170 var dstPointMat = new MatOfPoint2f(dstPoints); 171 // the rectangle describing the rectangle-of-interest(ROI) 172 var boundingRect = Imgproc.boundingRect(dstPointMat); 173 // find the perspective transform from the tag image to the warped destination points 174 Mat perspecTrf = Imgproc.getPerspectiveTransform(tagPoints, dstPointMat); 175 // check extreme image corners after transform to check if we need to expand bounding rect 176 var extremeCorners = new MatOfPoint2f(); 177 Core.perspectiveTransform(tagImageCorners, extremeCorners, perspecTrf); 178 // dilate ROI to fit full tag 179 boundingRect = Imgproc.boundingRect(extremeCorners); 180 181 // adjust interpolation strategy based on size of warped tag compared to tag image 182 var warpedContourArea = Imgproc.contourArea(extremeCorners); 183 double warpedTagUpscale = Math.sqrt(warpedContourArea) / Math.sqrt(tagImage.size().area()); 184 int warpStrategy = Imgproc.INTER_NEAREST; 185 // automatically determine the best supersampling of warped image and scale of tag image 186 /* 187 (warpPerspective does not properly resample, so this is used to avoid aliasing in the 188 warped image. Supersampling is used when the warped tag is small, but is very slow 189 when the warped tag is large-- scaling the tag image up and using linear interpolation 190 instead can be performant while still effectively antialiasing. Some combination of these 191 two can be used in between those extremes.) 192 193 TODO: Simplify magic numbers to one or two variables, or use a more proper approach? 194 */ 195 int supersampling = 6; 196 supersampling = (int) Math.ceil(supersampling / warpedTagUpscale); 197 supersampling = Math.max(Math.min(supersampling, 10), 1); 198 199 Mat scaledTagImage = new Mat(); 200 if (warpedTagUpscale > 2.0) { 201 warpStrategy = Imgproc.INTER_LINEAR; 202 int scaleFactor = (int) (warpedTagUpscale / 3.0) + 2; 203 scaleFactor = Math.max(Math.min(scaleFactor, 40), 1); 204 scaleFactor *= supersampling; 205 Imgproc.resize( 206 tagImage, scaledTagImage, new Size(), scaleFactor, scaleFactor, Imgproc.INTER_NEAREST); 207 tagPoints.fromArray(get36h11MarkerPts(scaleFactor)); 208 } else tagImage.assignTo(scaledTagImage); 209 210 // constrain the bounding rect inside of the destination image 211 boundingRect.x -= 1; 212 boundingRect.y -= 1; 213 boundingRect.width += 2; 214 boundingRect.height += 2; 215 if (boundingRect.x < 0) { 216 boundingRect.width += boundingRect.x; 217 boundingRect.x = 0; 218 } 219 if (boundingRect.y < 0) { 220 boundingRect.height += boundingRect.y; 221 boundingRect.y = 0; 222 } 223 boundingRect.width = Math.min(destination.width() - boundingRect.x, boundingRect.width); 224 boundingRect.height = Math.min(destination.height() - boundingRect.y, boundingRect.height); 225 if (boundingRect.width <= 0 || boundingRect.height <= 0) return; 226 227 // upscale if supersampling 228 Mat scaledDstPts = new Mat(); 229 if (supersampling > 1) { 230 Core.multiply(dstPointMat, new Scalar(supersampling, supersampling), scaledDstPts); 231 boundingRect.x *= supersampling; 232 boundingRect.y *= supersampling; 233 boundingRect.width *= supersampling; 234 boundingRect.height *= supersampling; 235 } else dstPointMat.assignTo(scaledDstPts); 236 237 // update transform relative to expanded, scaled bounding rect 238 Core.subtract(scaledDstPts, new Scalar(boundingRect.tl().x, boundingRect.tl().y), scaledDstPts); 239 perspecTrf = Imgproc.getPerspectiveTransform(tagPoints, scaledDstPts); 240 241 // warp (scaled) tag image onto (scaled) ROI image representing the portion of 242 // the destination image encapsulated by boundingRect 243 Mat tempROI = new Mat(); 244 Imgproc.warpPerspective(scaledTagImage, tempROI, perspecTrf, boundingRect.size(), warpStrategy); 245 246 // downscale ROI with interpolation if supersampling 247 if (supersampling > 1) { 248 boundingRect.x /= supersampling; 249 boundingRect.y /= supersampling; 250 boundingRect.width /= supersampling; 251 boundingRect.height /= supersampling; 252 Imgproc.resize(tempROI, tempROI, boundingRect.size(), 0, 0, Imgproc.INTER_AREA); 253 } 254 255 // we want to copy ONLY the transformed tag to the result image, not the entire bounding rect 256 // using a mask only copies the source pixels which have an associated non-zero value in the 257 // mask 258 Mat tempMask = Mat.zeros(tempROI.size(), CvType.CV_8UC1); 259 Core.subtract( 260 extremeCorners, new Scalar(boundingRect.tl().x, boundingRect.tl().y), extremeCorners); 261 Point tempCenter = new Point(); 262 tempCenter.x = 263 Arrays.stream(extremeCorners.toArray()).mapToDouble(p -> p.x).average().getAsDouble(); 264 tempCenter.y = 265 Arrays.stream(extremeCorners.toArray()).mapToDouble(p -> p.y).average().getAsDouble(); 266 // dilate tag corners 267 Arrays.stream(extremeCorners.toArray()) 268 .forEach( 269 p -> { 270 double xdiff = p.x - tempCenter.x; 271 double ydiff = p.y - tempCenter.y; 272 xdiff += 1 * Math.signum(xdiff); 273 ydiff += 1 * Math.signum(ydiff); 274 new Point(tempCenter.x + xdiff, tempCenter.y + ydiff); 275 }); 276 // (make inside of tag completely white in mask) 277 Imgproc.fillConvexPoly(tempMask, new MatOfPoint(extremeCorners.toArray()), new Scalar(255)); 278 279 // copy transformed tag onto result image 280 tempROI.copyTo(destination.submat(boundingRect), tempMask); 281 } 282 283 /** 284 * Given a line thickness in a 640x480 image, try to scale to the given destination image 285 * resolution. 286 * 287 * @param thickness480p A hypothetical line thickness in a 640x480 image 288 * @param destination The destination image to scale to 289 * @return Scaled thickness which cannot be less than 1 290 */ 291 public static double getScaledThickness(double thickness480p, Mat destination) { 292 double scaleX = destination.width() / 640.0; 293 double scaleY = destination.height() / 480.0; 294 double minScale = Math.min(scaleX, scaleY); 295 return Math.max(thickness480p * minScale, 1.0); 296 } 297 298 /** 299 * Draw a filled ellipse in the destination image. 300 * 301 * @param dstPoints The points in the destination image representing the rectangle in which the 302 * ellipse is inscribed. 303 * @param color The color of the ellipse. This is a scalar with BGR values (0-255) 304 * @param destination The destination image to draw onto. The image should be in the BGR color 305 * space. 306 */ 307 public static void drawInscribedEllipse(Point[] dstPoints, Scalar color, Mat destination) { 308 // create RotatedRect from points 309 var rect = OpenCVHelp.getMinAreaRect(dstPoints); 310 // inscribe ellipse inside rectangle 311 Imgproc.ellipse(destination, rect, color, -1, Imgproc.LINE_AA); 312 } 313 314 /** 315 * Draw a polygon outline or filled polygon to the destination image with the given points. 316 * 317 * @param dstPoints The points in the destination image representing the polygon. 318 * @param thickness The thickness of the outline in pixels. If this is not positive, a filled 319 * polygon is drawn instead. 320 * @param color The color drawn. This should match the color space of the destination image. 321 * @param isClosed If the last point should connect to the first point in the polygon outline. 322 * @param destination The destination image to draw onto. 323 */ 324 public static void drawPoly( 325 Point[] dstPoints, int thickness, Scalar color, boolean isClosed, Mat destination) { 326 var dstPointsd = new MatOfPoint(dstPoints); 327 if (thickness > 0) { 328 Imgproc.polylines( 329 destination, List.of(dstPointsd), isClosed, color, thickness, Imgproc.LINE_AA); 330 } else { 331 Imgproc.fillPoly(destination, List.of(dstPointsd), color, Imgproc.LINE_AA); 332 } 333 } 334 335 /** 336 * Draws a contour around the given points and text of the id onto the destination image. 337 * 338 * @param id Fiducial ID number to draw 339 * @param dstPoints Points representing the four corners of the tag marker(black square) in the 340 * destination image. 341 * @param destination The destination image to draw onto. The image should be in the BGR color 342 * space. 343 */ 344 public static void drawTagDetection(int id, Point[] dstPoints, Mat destination) { 345 double thickness = getScaledThickness(1, destination); 346 drawPoly(dstPoints, (int) thickness, new Scalar(0, 0, 255), true, destination); 347 var rect = Imgproc.boundingRect(new MatOfPoint(dstPoints)); 348 var textPt = new Point(rect.x + rect.width, rect.y); 349 textPt.x += thickness; 350 textPt.y += thickness; 351 Imgproc.putText( 352 destination, 353 String.valueOf(id), 354 textPt, 355 Imgproc.FONT_HERSHEY_PLAIN, 356 1.5 * thickness, 357 new Scalar(0, 200, 0), 358 (int) thickness, 359 Imgproc.LINE_AA); 360 } 361 362 /** 363 * Set the field dimensions that are used for drawing the field wireframe. 364 * 365 * @param fieldLengthMeters field length in meters (x direction) 366 * @param fieldWidthMeters field width in meters (y direction) 367 */ 368 public static void setFieldDimensionsMeters(double fieldLengthMeters, double fieldWidthMeters) { 369 fieldLength = fieldLengthMeters; 370 fieldWidth = fieldWidthMeters; 371 } 372 373 /** 374 * The translations used to draw the field side walls and driver station walls. It is a List of 375 * Lists because the translations are not all connected. 376 */ 377 private static List<List<Translation3d>> getFieldWallLines() { 378 var list = new ArrayList<List<Translation3d>>(); 379 380 final double sideHt = Units.inchesToMeters(19.5); 381 final double driveHt = Units.inchesToMeters(35); 382 final double topHt = Units.inchesToMeters(78); 383 384 // field floor 385 list.add( 386 List.of( 387 new Translation3d(0, 0, 0), 388 new Translation3d(fieldLength, 0, 0), 389 new Translation3d(fieldLength, fieldWidth, 0), 390 new Translation3d(0, fieldWidth, 0), 391 new Translation3d(0, 0, 0))); 392 // right side wall 393 list.add( 394 List.of( 395 new Translation3d(0, 0, 0), 396 new Translation3d(0, 0, sideHt), 397 new Translation3d(fieldLength, 0, sideHt), 398 new Translation3d(fieldLength, 0, 0))); 399 // red driverstation 400 list.add( 401 List.of( 402 new Translation3d(fieldLength, 0, sideHt), 403 new Translation3d(fieldLength, 0, topHt), 404 new Translation3d(fieldLength, fieldWidth, topHt), 405 new Translation3d(fieldLength, fieldWidth, sideHt))); 406 list.add( 407 List.of( 408 new Translation3d(fieldLength, 0, driveHt), 409 new Translation3d(fieldLength, fieldWidth, driveHt))); 410 // left side wall 411 list.add( 412 List.of( 413 new Translation3d(0, fieldWidth, 0), 414 new Translation3d(0, fieldWidth, sideHt), 415 new Translation3d(fieldLength, fieldWidth, sideHt), 416 new Translation3d(fieldLength, fieldWidth, 0))); 417 // blue driverstation 418 list.add( 419 List.of( 420 new Translation3d(0, 0, sideHt), 421 new Translation3d(0, 0, topHt), 422 new Translation3d(0, fieldWidth, topHt), 423 new Translation3d(0, fieldWidth, sideHt))); 424 list.add(List.of(new Translation3d(0, 0, driveHt), new Translation3d(0, fieldWidth, driveHt))); 425 426 return list; 427 } 428 429 /** 430 * The translations used to draw the field floor subdivisions (not the floor outline). It is a 431 * List of Lists because the translations are not all connected. 432 * 433 * @param subdivisions How many "subdivisions" along the width/length of the floor. E.g. 3 434 * subdivisions would mean 2 lines along the length and 2 lines along the width creating a 3x3 435 * "grid". 436 */ 437 private static List<List<Translation3d>> getFieldFloorLines(int subdivisions) { 438 var list = new ArrayList<List<Translation3d>>(); 439 final double subLength = fieldLength / subdivisions; 440 final double subWidth = fieldWidth / subdivisions; 441 442 // field floor subdivisions 443 for (int i = 0; i < subdivisions; i++) { 444 list.add( 445 List.of( 446 new Translation3d(0, subWidth * (i + 1), 0), 447 new Translation3d(fieldLength, subWidth * (i + 1), 0))); 448 list.add( 449 List.of( 450 new Translation3d(subLength * (i + 1), 0, 0), 451 new Translation3d(subLength * (i + 1), fieldWidth, 0))); 452 } 453 454 return list; 455 } 456 457 /** 458 * Convert 3D lines represented by the given series of translations into a polygon(s) in the 459 * camera's image. 460 * 461 * @param camRt The change in basis from world coordinates to camera coordinates. See {@link 462 * RotTrlTransform3d#makeRelativeTo(Pose3d)}. 463 * @param prop The simulated camera's properties. 464 * @param trls A sequential series of translations defining the polygon to be drawn. 465 * @param resolution Resolution as a fraction(0 - 1) of the video frame's diagonal length in 466 * pixels. Line segments will be subdivided if they exceed this resolution. 467 * @param isClosed If the final translation should also draw a line to the first translation. 468 * @param destination The destination image that is being drawn to. 469 * @return A list of polygons(which are an array of points) 470 */ 471 public static List<Point[]> polyFrom3dLines( 472 RotTrlTransform3d camRt, 473 SimCameraProperties prop, 474 List<Translation3d> trls, 475 double resolution, 476 boolean isClosed, 477 Mat destination) { 478 resolution = Math.hypot(destination.size().height, destination.size().width) * resolution; 479 List<Translation3d> pts = new ArrayList<>(trls); 480 if (isClosed) pts.add(pts.get(0)); 481 List<Point[]> polyPointList = new ArrayList<>(); 482 483 for (int i = 0; i < pts.size() - 1; i++) { 484 var pta = pts.get(i); 485 var ptb = pts.get(i + 1); 486 487 // check if line is inside camera fulcrum 488 var inter = prop.getVisibleLine(camRt, pta, ptb); 489 if (inter.getSecond() == null) continue; 490 491 // cull line to the inside of the camera fulcrum 492 double inter1 = inter.getFirst(); 493 double inter2 = inter.getSecond(); 494 var baseDelta = ptb.minus(pta); 495 var old_pta = pta; 496 if (inter1 > 0) pta = old_pta.plus(baseDelta.times(inter1)); 497 if (inter2 < 1) ptb = old_pta.plus(baseDelta.times(inter2)); 498 baseDelta = ptb.minus(pta); 499 500 // project points into 2d 501 var poly = 502 new ArrayList<>( 503 Arrays.asList( 504 OpenCVHelp.projectPoints( 505 prop.getIntrinsics(), prop.getDistCoeffs(), camRt, List.of(pta, ptb)))); 506 var pxa = poly.get(0); 507 var pxb = poly.get(1); 508 509 // subdivide projected line based on desired resolution 510 double pxDist = Math.hypot(pxb.x - pxa.x, pxb.y - pxa.y); 511 int subdivisions = (int) (pxDist / resolution); 512 var subDelta = baseDelta.div(subdivisions + 1); 513 var subPts = new ArrayList<Translation3d>(); 514 for (int j = 0; j < subdivisions; j++) { 515 subPts.add(pta.plus(subDelta.times(j + 1))); 516 } 517 if (!subPts.isEmpty()) { 518 poly.addAll( 519 1, 520 Arrays.asList( 521 OpenCVHelp.projectPoints( 522 prop.getIntrinsics(), prop.getDistCoeffs(), camRt, subPts))); 523 } 524 525 polyPointList.add(poly.toArray(Point[]::new)); 526 } 527 528 return polyPointList; 529 } 530 531 /** 532 * Draw a wireframe of the field to the given image. 533 * 534 * @param camRt The change in basis from world coordinates to camera coordinates. See {@link 535 * RotTrlTransform3d#makeRelativeTo(Pose3d)}. 536 * @param prop The simulated camera's properties. 537 * @param resolution Resolution as a fraction(0 - 1) of the video frame's diagonal length in 538 * pixels. Line segments will be subdivided if they exceed this resolution. 539 * @param wallThickness Thickness of the lines used for drawing the field walls in pixels. This is 540 * scaled by {@link #getScaledThickness(double, Mat)}. 541 * @param wallColor Color of the lines used for drawing the field walls. 542 * @param floorSubdivisions A NxN "grid" is created from the floor where this parameter is N, 543 * which defines the floor lines. 544 * @param floorThickness Thickness of the lines used for drawing the field floor grid in pixels. 545 * This is scaled by {@link #getScaledThickness(double, Mat)}. 546 * @param floorColor Color of the lines used for drawing the field floor grid. 547 * @param destination The destination image to draw to. 548 */ 549 public static void drawFieldWireframe( 550 RotTrlTransform3d camRt, 551 SimCameraProperties prop, 552 double resolution, 553 double wallThickness, 554 Scalar wallColor, 555 int floorSubdivisions, 556 double floorThickness, 557 Scalar floorColor, 558 Mat destination) { 559 for (var trls : getFieldFloorLines(floorSubdivisions)) { 560 var polys = VideoSimUtil.polyFrom3dLines(camRt, prop, trls, resolution, false, destination); 561 for (var poly : polys) { 562 drawPoly( 563 poly, 564 (int) Math.round(getScaledThickness(floorThickness, destination)), 565 floorColor, 566 false, 567 destination); 568 } 569 } 570 for (var trls : getFieldWallLines()) { 571 var polys = VideoSimUtil.polyFrom3dLines(camRt, prop, trls, resolution, false, destination); 572 for (var poly : polys) { 573 drawPoly( 574 poly, 575 (int) Math.round(getScaledThickness(wallThickness, destination)), 576 wallColor, 577 false, 578 destination); 579 } 580 } 581 } 582}