Class TargetModel

java.lang.Object
org.photonvision.estimation.TargetModel

public class TargetModel extends Object
Describes the 3d model of a target.
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    final boolean
     
    final boolean
     
    static final TargetModel
     
    static final TargetModel
     
    final List<edu.wpi.first.math.geometry.Translation3d>
    Translations of this target's vertices relative to its pose.
  • Constructor Summary

    Constructors
    Constructor
    Description
    TargetModel(double diameterMeters)
    Creates a spherical target model which has similar dimensions regardless of its rotation.
    TargetModel(double widthMeters, double heightMeters)
    Creates a rectangular, planar target model given the width and height.
    TargetModel(double lengthMeters, double widthMeters, double heightMeters)
    Creates a cuboid target model given the length, width, height.
    TargetModel(List<edu.wpi.first.math.geometry.Translation3d> vertices)
    Creates a target model from arbitrary 3d vertices.
  • Method Summary

    Modifier and Type
    Method
    Description
    boolean
     
    List<edu.wpi.first.math.geometry.Translation3d>
    getFieldVertices(edu.wpi.first.math.geometry.Pose3d targetPose)
    This target's vertices offset from its field pose.
    static edu.wpi.first.math.geometry.Pose3d
    getOrientedPose(edu.wpi.first.math.geometry.Translation3d tgtTrl, edu.wpi.first.math.geometry.Translation3d cameraTrl)
    Returns a Pose3d with the given target translation oriented (with its relative x-axis aligned) to the camera translation.

    Methods inherited from class java.lang.Object

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

    • vertices

      public final List<edu.wpi.first.math.geometry.Translation3d> vertices
      Translations of this target's vertices relative to its pose. Rectangular and spherical targets will have four vertices. See their respective constructors for more info.
    • isPlanar

      public final boolean isPlanar
    • isSpherical

      public final boolean isSpherical
    • kAprilTag16h5

      public static final TargetModel kAprilTag16h5
    • kAprilTag36h11

      public static final TargetModel kAprilTag36h11
  • Constructor Details

    • TargetModel

      public TargetModel(double widthMeters, double heightMeters)
      Creates a rectangular, planar target model given the width and height. The model has four vertices:
      • Point 0: [0, -width/2, -height/2]
      • Point 1: [0, width/2, -height/2]
      • Point 2: [0, width/2, height/2]
      • Point 3: [0, -width/2, height/2]
    • TargetModel

      public TargetModel(double lengthMeters, double widthMeters, double heightMeters)
      Creates a cuboid target model given the length, width, height. The model has eight vertices:
      • Point 0: [length/2, -width/2, -height/2]
      • Point 1: [length/2, width/2, -height/2]
      • Point 2: [length/2, width/2, height/2]
      • Point 3: [length/2, -width/2, height/2]
      • Point 4: [-length/2, -width/2, height/2]
      • Point 5: [-length/2, width/2, height/2]
      • Point 6: [-length/2, width/2, -height/2]
      • Point 7: [-length/2, -width/2, -height/2]
    • TargetModel

      public TargetModel(double diameterMeters)
      Creates a spherical target model which has similar dimensions regardless of its rotation. This model has four vertices:
      • Point 0: [0, -radius, 0]
      • Point 1: [0, 0, -radius]
      • Point 2: [0, radius, 0]
      • Point 3: [0, 0, radius]
      Q: Why these vertices? A: This target should be oriented to the camera every frame, much like a sprite/decal, and these vertices represent the ellipse vertices (maxima). These vertices are used for drawing the image of this sphere, but do not match the corners that will be published by photonvision.
    • TargetModel

      public TargetModel(List<edu.wpi.first.math.geometry.Translation3d> vertices)
      Creates a target model from arbitrary 3d vertices. Automatically determines if the given vertices are planar(x == 0). More than 2 vertices must be given. If this is a planar model, the vertices should define a non-intersecting contour.
      Parameters:
      vertices - Translations representing the vertices of this target model relative to its pose.
  • Method Details

    • getFieldVertices

      public List<edu.wpi.first.math.geometry.Translation3d> getFieldVertices(edu.wpi.first.math.geometry.Pose3d targetPose)
      This target's vertices offset from its field pose.

      Note: If this target is spherical, use getOrientedPose(Translation3d, Translation3d) with this method.

    • getOrientedPose

      public static edu.wpi.first.math.geometry.Pose3d getOrientedPose(edu.wpi.first.math.geometry.Translation3d tgtTrl, edu.wpi.first.math.geometry.Translation3d cameraTrl)
      Returns a Pose3d with the given target translation oriented (with its relative x-axis aligned) to the camera translation. This is used for spherical targets which should not have their projection change regardless of their own rotation.
      Parameters:
      tgtTrl - This target's translation
      cameraTrl - Camera's translation
      Returns:
      This target's pose oriented to the camera
    • equals

      public boolean equals(Object obj)
      Overrides:
      equals in class Object