Class AprilTagDetection

java.lang.Object
edu.wpi.first.apriltag.AprilTagDetection

public class AprilTagDetection
extends Object
A detection of an AprilTag tag.
  • Constructor Summary

    Constructors 
    Constructor Description
    AprilTagDetection​(String family, int id, int hamming, float decisionMargin, double[] homography, double centerX, double centerY, double[] corners)
    Constructs a new detection result.
  • Method Summary

    Modifier and Type Method Description
    double getCenterX()
    Gets the center of the detection in image pixel coordinates.
    double getCenterY()
    Gets the center of the detection in image pixel coordinates.
    double[] getCorners()
    Gets the corners of the tag in image pixel coordinates.
    double getCornerX​(int ndx)
    Gets a corner of the tag in image pixel coordinates.
    double getCornerY​(int ndx)
    Gets a corner of the tag in image pixel coordinates.
    float getDecisionMargin()
    Gets a measure of the quality of the binary decoding process: the average difference between the intensity of a data bit versus the decision threshold.
    String getFamily()
    Gets the decoded tag's family name.
    int getHamming()
    Gets how many error bits were corrected.
    double[] getHomography()
    Gets the 3x3 homography matrix describing the projection from an "ideal" tag (with corners at (-1,1), (1,1), (1,-1), and (-1, -1)) to pixels in the image.
    Matrix<N3,​N3> getHomographyMatrix()
    Gets the 3x3 homography matrix describing the projection from an "ideal" tag (with corners at (-1,1), (1,1), (1,-1), and (-1, -1)) to pixels in the image.
    int getId()
    Gets the decoded ID of the tag.
    String toString()  

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, wait, wait, wait
  • Constructor Details

    • AprilTagDetection

      public AprilTagDetection​(String family, int id, int hamming, float decisionMargin, double[] homography, double centerX, double centerY, double[] corners)
      Constructs a new detection result. Used from JNI.
      Parameters:
      family - family
      id - id
      hamming - hamming
      decisionMargin - dm
      homography - homography
      centerX - centerX
      centerY - centerY
      corners - corners
  • Method Details

    • getFamily

      public String getFamily()
      Gets the decoded tag's family name.
      Returns:
      Decoded family name
    • getId

      public int getId()
      Gets the decoded ID of the tag.
      Returns:
      Decoded ID
    • getHamming

      public int getHamming()
      Gets how many error bits were corrected. Note: accepting large numbers of corrected errors leads to greatly increased false positive rates. NOTE: As of this implementation, the detector cannot detect tags with a hamming distance greater than 2.
      Returns:
      Hamming distance (number of corrected error bits)
    • getDecisionMargin

      public float getDecisionMargin()
      Gets a measure of the quality of the binary decoding process: the average difference between the intensity of a data bit versus the decision threshold. Higher numbers roughly indicate better decodes. This is a reasonable measure of detection accuracy only for very small tags-- not effective for larger tags (where we could have sampled anywhere within a bit cell and still gotten a good detection.)
      Returns:
      Decision margin
    • getHomography

      public double[] getHomography()
      Gets the 3x3 homography matrix describing the projection from an "ideal" tag (with corners at (-1,1), (1,1), (1,-1), and (-1, -1)) to pixels in the image.
      Returns:
      Homography matrix data
    • getHomographyMatrix

      Gets the 3x3 homography matrix describing the projection from an "ideal" tag (with corners at (-1,1), (1,1), (1,-1), and (-1, -1)) to pixels in the image.
      Returns:
      Homography matrix
    • getCenterX

      public double getCenterX()
      Gets the center of the detection in image pixel coordinates.
      Returns:
      Center point X coordinate
    • getCenterY

      public double getCenterY()
      Gets the center of the detection in image pixel coordinates.
      Returns:
      Center point Y coordinate
    • getCornerX

      public double getCornerX​(int ndx)
      Gets a corner of the tag in image pixel coordinates. These always wrap counter-clock wise around the tag.
      Parameters:
      ndx - Corner index (range is 0-3, inclusive)
      Returns:
      Corner point X coordinate
    • getCornerY

      public double getCornerY​(int ndx)
      Gets a corner of the tag in image pixel coordinates. These always wrap counter-clock wise around the tag.
      Parameters:
      ndx - Corner index (range is 0-3, inclusive)
      Returns:
      Corner point Y coordinate
    • getCorners

      public double[] getCorners()
      Gets the corners of the tag in image pixel coordinates. These always wrap counter-clock wise around the tag.
      Returns:
      Corner point array (X and Y for each corner in order)
    • toString

      public String toString()
      Overrides:
      toString in class Object