Class AprilTagJNI

java.lang.Object
edu.wpi.first.apriltag.jni.AprilTagJNI

public class AprilTagJNI
extends Object
AprilTag JNI.
  • Method Details

    • createDetector

      public static long createDetector()
      Constructs an AprilTag detector engine.
      Returns:
      The detector engine handle
    • destroyDetector

      public static void destroyDetector​(long det)
      Destroys an AprilTag detector engine.
      Parameters:
      det - The detector engine handle
    • setDetectorConfig

      public static void setDetectorConfig​(long det, AprilTagDetector.Config config)
      Sets the detector engine configuration.
      Parameters:
      det - The detector engine handle
      config - A configuration
    • getDetectorConfig

      public static AprilTagDetector.Config getDetectorConfig​(long det)
      Gets the detector engine configuration.
      Parameters:
      det - The detector engine handle
      Returns:
      The configuration
    • setDetectorQTP

      public static void setDetectorQTP​(long det, AprilTagDetector.QuadThresholdParameters params)
      Sets the detector engine quad threshold parameters.
      Parameters:
      det - The detector engine handle
      params - Quad threshold parameters
    • getDetectorQTP

      Gets the detector engine quad threshold parameters.
      Parameters:
      det - The detector engine handle
      Returns:
      Quad threshold parameters
    • addFamily

      public static boolean addFamily​(long det, String fam, int bitsCorrected)
      Adds a family of tags to be detected by the detector engine.
      Parameters:
      det - The detector engine handle
      fam - Family name, e.g. "tag16h5"
      bitsCorrected - Maximum number of bits to correct
      Returns:
      False if family can't be found
    • removeFamily

      public static void removeFamily​(long det, String fam)
      Removes a family of tags from the detector.
      Parameters:
      det - The detector engine handle
      fam - Family name, e.g. "tag16h5"
    • clearFamilies

      public static void clearFamilies​(long det)
      Unregister all families.
      Parameters:
      det - The detector engine handle
    • detect

      public static AprilTagDetection[] detect​(long det, int width, int height, int stride, long bufAddr)
      Detect tags from an 8-bit image.
      Parameters:
      det - The detector engine handle
      width - The width of the image
      height - The height of the image
      stride - The number of bytes between image rows (often the same as width)
      bufAddr - The address of the image buffer
      Returns:
      The results (array of AprilTagDetection)
    • estimatePoseHomography

      public static Transform3d estimatePoseHomography​(double[] homography, double tagSize, double fx, double fy, double cx, double cy)
      Estimates the pose of the tag using the homography method described in [1].
      Parameters:
      homography - Homography 3x3 matrix data
      tagSize - The tag size, in meters
      fx - The camera horizontal focal length, in pixels
      fy - The camera vertical focal length, in pixels
      cx - The camera horizontal focal center, in pixels
      cy - The camera vertical focal center, in pixels
      Returns:
      Pose estimate
    • estimatePoseOrthogonalIteration

      public static AprilTagPoseEstimate estimatePoseOrthogonalIteration​(double[] homography, double[] corners, double tagSize, double fx, double fy, double cx, double cy, int nIters)
      Estimates the pose of the tag. This returns one or two possible poses for the tag, along with the object-space error of each.
      Parameters:
      homography - Homography 3x3 matrix data
      corners - Corner point array (X and Y for each corner in order)
      tagSize - The tag size, in meters
      fx - The camera horizontal focal length, in pixels
      fy - The camera vertical focal length, in pixels
      cx - The camera horizontal focal center, in pixels
      cy - The camera vertical focal center, in pixels
      nIters - Number of iterations
      Returns:
      Initial and (possibly) second pose estimates
    • estimatePose

      public static Transform3d estimatePose​(double[] homography, double[] corners, double tagSize, double fx, double fy, double cx, double cy)
      Estimates tag pose. This method is an easier to use interface to EstimatePoseOrthogonalIteration(), running 50 iterations and returning the pose with the lower object-space error.
      Parameters:
      homography - Homography 3x3 matrix data
      corners - Corner point array (X and Y for each corner in order)
      tagSize - The tag size, in meters
      fx - The camera horizontal focal length, in pixels
      fy - The camera vertical focal length, in pixels
      cx - The camera horizontal focal center, in pixels
      cy - The camera vertical focal center, in pixels
      Returns:
      Pose estimate
    • generate16h5AprilTagImage

      public static void generate16h5AprilTagImage​(RawFrame frameObj, long frame, int id)
      Generates a RawFrame containing the apriltag with the id with family 16h5 passed in.
      Parameters:
      frameObj - generated frame (output parameter).
      frame - raw frame handle
      id - id
    • generate36h11AprilTagImage

      public static void generate36h11AprilTagImage​(RawFrame frameObj, long frame, int id)
      Generates a RawFrame containing the apriltag with the id with family 36h11 passed in.
      Parameters:
      frameObj - generated frame (output parameter).
      frame - raw frame handle
      id - id