Class VideoSimUtil

java.lang.Object
org.photonvision.simulation.VideoSimUtil

public class VideoSimUtil extends Object
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    static final int
     
    static final org.opencv.core.Point[]
     
  • Constructor Summary

    Constructors
    Constructor
    Description
     
  • Method Summary

    Modifier and Type
    Method
    Description
    static void
    drawFieldWireframe(RotTrlTransform3d camRt, SimCameraProperties prop, double resolution, double wallThickness, org.opencv.core.Scalar wallColor, int floorSubdivisions, double floorThickness, org.opencv.core.Scalar floorColor, org.opencv.core.Mat destination)
    Draw a wireframe of the field to the given image.
    static void
    drawInscribedEllipse(org.opencv.core.Point[] dstPoints, org.opencv.core.Scalar color, org.opencv.core.Mat destination)
    Draw a filled ellipse in the destination image.
    static void
    drawPoly(org.opencv.core.Point[] dstPoints, int thickness, org.opencv.core.Scalar color, boolean isClosed, org.opencv.core.Mat destination)
    Draw a polygon outline or filled polygon to the destination image with the given points.
    static void
    drawTagDetection(int id, org.opencv.core.Point[] dstPoints, org.opencv.core.Mat destination)
    Draws a contour around the given points and text of the id onto the destination image.
    static org.opencv.core.Point[]
    Gets the points representing the marker(black square) corners.
    static org.opencv.core.Point[]
    get36h11MarkerPts(int scale)
    Gets the points representing the marker(black square) corners.
    static org.opencv.core.Mat
    Gets the 10x10 (grayscale) image of a specific 36h11 AprilTag.
    static org.opencv.core.Point[]
    getImageCorners(org.opencv.core.Size size)
    Gets the points representing the corners of this image.
    static double
    getScaledThickness(double thickness480p, org.opencv.core.Mat destinationImg)
    Given a line thickness in a 640x480 image, try to scale to the given destination image resolution.
    static List<org.opencv.core.Point[]>
    polyFrom3dLines(RotTrlTransform3d camRt, SimCameraProperties prop, List<edu.wpi.first.math.geometry.Translation3d> trls, double resolution, boolean isClosed, org.opencv.core.Mat destination)
    Convert 3D lines represented by the given series of translations into a polygon(s) in the camera's image.
    static void
    setFieldDimensionsMeters(double fieldLengthMeters, double fieldWidthMeters)
    Set the field dimensions that are used for drawing the field wireframe.
    static void
    updateVideoProp(edu.wpi.first.cscore.CvSource video, SimCameraProperties prop)
    Updates the properties of this CvSource video stream with the given camera properties.
    static void
    warp36h11TagImage(int tagId, org.opencv.core.Point[] dstPoints, boolean antialiasing, org.opencv.core.Mat destination)
    Warps the image of a specific 36h11 AprilTag onto the destination image at the given points.

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Field Details

    • kNumTags36h11

      public static final int kNumTags36h11
      See Also:
    • kTag36h11MarkerPts

      public static final org.opencv.core.Point[] kTag36h11MarkerPts
  • Constructor Details

    • VideoSimUtil

      public VideoSimUtil()
  • Method Details

    • updateVideoProp

      public static void updateVideoProp(edu.wpi.first.cscore.CvSource video, SimCameraProperties prop)
      Updates the properties of this CvSource video stream with the given camera properties.
    • getImageCorners

      public static org.opencv.core.Point[] getImageCorners(org.opencv.core.Size size)
      Gets the points representing the corners of this image. Because image pixels are accessed through a Mat, the point (0,0) actually represents the center of the top-left pixel and not the actual top-left corner.
      Parameters:
      size - Size of image
    • get36h11TagImage

      public static org.opencv.core.Mat get36h11TagImage(int id)
      Gets the 10x10 (grayscale) image of a specific 36h11 AprilTag.
      Parameters:
      id - The fiducial id of the desired tag
    • get36h11MarkerPts

      public static org.opencv.core.Point[] get36h11MarkerPts()
      Gets the points representing the marker(black square) corners.
    • get36h11MarkerPts

      public static org.opencv.core.Point[] get36h11MarkerPts(int scale)
      Gets the points representing the marker(black square) corners.
      Parameters:
      scale - The scale of the tag image (10*scale x 10*scale image)
    • warp36h11TagImage

      public static void warp36h11TagImage(int tagId, org.opencv.core.Point[] dstPoints, boolean antialiasing, org.opencv.core.Mat destination)
      Warps the image of a specific 36h11 AprilTag onto the destination image at the given points.
      Parameters:
      tagId - The id of the specific tag to warp onto the destination image
      dstPoints - Points(4) in destination image where the tag marker(black square) corners should be warped onto.
      antialiasing - If antialiasing should be performed by automatically supersampling/interpolating the warped image. This should be used if better stream quality is desired or target detection is being done on the stream, but can hurt performance.
      destination - The destination image to place the warped tag image onto.
    • getScaledThickness

      public static double getScaledThickness(double thickness480p, org.opencv.core.Mat destinationImg)
      Given a line thickness in a 640x480 image, try to scale to the given destination image resolution.
      Parameters:
      thickness480p - A hypothetical line thickness in a 640x480 image
      destinationImg - The destination image to scale to
      Returns:
      Scaled thickness which cannot be less than 1
    • drawInscribedEllipse

      public static void drawInscribedEllipse(org.opencv.core.Point[] dstPoints, org.opencv.core.Scalar color, org.opencv.core.Mat destination)
      Draw a filled ellipse in the destination image.
      Parameters:
      dstPoints - The points in the destination image representing the rectangle in which the ellipse is inscribed.
      color - The color of the ellipse. This is a scalar with BGR values (0-255)
      destination - The destination image to draw onto. The image should be in the BGR color space.
    • drawPoly

      public static void drawPoly(org.opencv.core.Point[] dstPoints, int thickness, org.opencv.core.Scalar color, boolean isClosed, org.opencv.core.Mat destination)
      Draw a polygon outline or filled polygon to the destination image with the given points.
      Parameters:
      dstPoints - The points in the destination image representing the polygon.
      thickness - The thickness of the outline in pixels. If this is not positive, a filled polygon is drawn instead.
      color - The color drawn. This should match the color space of the destination image.
      isClosed - If the last point should connect to the first point in the polygon outline.
      destination - The destination image to draw onto.
    • drawTagDetection

      public static void drawTagDetection(int id, org.opencv.core.Point[] dstPoints, org.opencv.core.Mat destination)
      Draws a contour around the given points and text of the id onto the destination image.
      Parameters:
      id - Fiducial ID number to draw
      dstPoints - Points representing the four corners of the tag marker(black square) in the destination image.
      destination - The destination image to draw onto. The image should be in the BGR color space.
    • setFieldDimensionsMeters

      public static void setFieldDimensionsMeters(double fieldLengthMeters, double fieldWidthMeters)
      Set the field dimensions that are used for drawing the field wireframe.
      Parameters:
      fieldLengthMeters - field length in meters (x direction)
      fieldWidthMeters - field width in meters (y direction)
    • polyFrom3dLines

      public static List<org.opencv.core.Point[]> polyFrom3dLines(RotTrlTransform3d camRt, SimCameraProperties prop, List<edu.wpi.first.math.geometry.Translation3d> trls, double resolution, boolean isClosed, org.opencv.core.Mat destination)
      Convert 3D lines represented by the given series of translations into a polygon(s) in the camera's image.
      Parameters:
      camRt - The change in basis from world coordinates to camera coordinates. See RotTrlTransform3d.makeRelativeTo(Pose3d).
      prop - The simulated camera's properties.
      trls - A sequential series of translations defining the polygon to be drawn.
      resolution - Resolution as a fraction(0 - 1) of the video frame's diagonal length in pixels. Line segments will be subdivided if they exceed this resolution.
      isClosed - If the final translation should also draw a line to the first translation.
      destination - The destination image that is being drawn to.
      Returns:
      A list of polygons(which are an array of points)
    • drawFieldWireframe

      public static void drawFieldWireframe(RotTrlTransform3d camRt, SimCameraProperties prop, double resolution, double wallThickness, org.opencv.core.Scalar wallColor, int floorSubdivisions, double floorThickness, org.opencv.core.Scalar floorColor, org.opencv.core.Mat destination)
      Draw a wireframe of the field to the given image.
      Parameters:
      camRt - The change in basis from world coordinates to camera coordinates. See RotTrlTransform3d.makeRelativeTo(Pose3d).
      prop - The simulated camera's properties.
      resolution - Resolution as a fraction(0 - 1) of the video frame's diagonal length in pixels. Line segments will be subdivided if they exceed this resolution.
      wallThickness - Thickness of the lines used for drawing the field walls in pixels. This is scaled by getScaledThickness(double, Mat).
      wallColor - Color of the lines used for drawing the field walls.
      floorSubdivisions - A NxN "grid" is created from the floor where this parameter is N, which defines the floor lines.
      floorThickness - Thickness of the lines used for drawing the field floor grid in pixels. This is scaled by getScaledThickness(double, Mat).
      floorColor - Color of the lines used for drawing the field floor grid.
      destination - The destination image to draw to.