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