Package edu.wpi.first.apriltag.jni
Class AprilTagJNI
java.lang.Object
edu.wpi.first.apriltag.jni.AprilTagJNI
public class AprilTagJNI extends Object
-
Nested Class Summary
Nested Classes Modifier and Type Class Description static class
AprilTagJNI.Helper
-
Constructor Summary
Constructors Constructor Description AprilTagJNI()
-
Method Summary
Modifier and Type Method Description static boolean
addFamily(long det, String fam, int bitsCorrected)
Adds a family of tags to be detected by the detector engine.static void
clearFamilies(long det)
Unregister all families.static long
createDetector()
Constructs an AprilTag detector engine.static void
destroyDetector(long det)
Destroys an AprilTag detector engine.static AprilTagDetection[]
detect(long det, int width, int height, int stride, long bufAddr)
Detect tags from an 8-bit image.static Transform3d
estimatePose(double[] homography, double[] corners, double tagSize, double fx, double fy, double cx, double cy)
Estimates tag pose.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].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.static void
generate16h5AprilTagImage(int id, long nativeAddr)
static void
generate36h11AprilTagImage(int id, long nativeAddr)
static AprilTagDetector.Config
getDetectorConfig(long det)
Gets the detector engine configuration.static AprilTagDetector.QuadThresholdParameters
getDetectorQTP(long det)
Gets the detector engine quad threshold parameters.static void
removeFamily(long det, String fam)
Removes a family of tags from the detector.static void
setDetectorConfig(long det, AprilTagDetector.Config config)
Sets the detector engine configuration.static void
setDetectorQTP(long det, AprilTagDetector.QuadThresholdParameters params)
Sets the detector engine quad threshold parameters.
-
Constructor Details
-
AprilTagJNI
public AprilTagJNI()
-
-
Method Details
-
createDetector
Constructs an AprilTag detector engine.- Returns:
- The detector engine handle
-
destroyDetector
Destroys an AprilTag detector engine.- Parameters:
det
- The detector engine handle
-
setDetectorConfig
Sets the detector engine configuration.- Parameters:
det
- The detector engine handleconfig
- A configuration
-
getDetectorConfig
Gets the detector engine configuration.- Parameters:
det
- The detector engine handle- Returns:
- The configuration
-
setDetectorQTP
Sets the detector engine quad threshold parameters.- Parameters:
det
- The detector engine handleparams
- Quad threshold parameters
-
getDetectorQTP
Gets the detector engine quad threshold parameters.- Parameters:
det
- The detector engine handle- Returns:
- Quad threshold parameters
-
addFamily
Adds a family of tags to be detected by the detector engine.- Parameters:
det
- The detector engine handlefam
- Family name, e.g. "tag16h5"bitsCorrected
- Maximum number of bits to correct- Returns:
- False if family can't be found
-
removeFamily
Removes a family of tags from the detector.- Parameters:
det
- The detector engine handlefam
- Family name, e.g. "tag16h5"
-
clearFamilies
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 handlewidth
- The width of the imageheight
- The height of the imagestride
- 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 datatagSize
- The tag size, in metersfx
- The camera horizontal focal length, in pixelsfy
- The camera vertical focal length, in pixelscx
- The camera horizontal focal center, in pixelscy
- 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 datacorners
- Corner point array (X and Y for each corner in order)tagSize
- The tag size, in metersfx
- The camera horizontal focal length, in pixelsfy
- The camera vertical focal length, in pixelscx
- The camera horizontal focal center, in pixelscy
- The camera vertical focal center, in pixelsnIters
- 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 datacorners
- Corner point array (X and Y for each corner in order)tagSize
- The tag size, in metersfx
- The camera horizontal focal length, in pixelsfy
- The camera vertical focal length, in pixelscx
- The camera horizontal focal center, in pixelscy
- The camera vertical focal center, in pixels- Returns:
- Pose estimate
-
generate16h5AprilTagImage
-
generate36h11AprilTagImage
-