Class AprilTagPoseEstimator
public class AprilTagPoseEstimator extends Object
-
Nested Class Summary
Nested Classes Modifier and Type Class Description static class
AprilTagPoseEstimator.Config
Configuration for the pose estimator. -
Constructor Summary
Constructors Constructor Description AprilTagPoseEstimator(AprilTagPoseEstimator.Config config)
Creates estimator. -
Method Summary
Modifier and Type Method Description Transform3d
estimate(double[] homography, double[] corners)
Estimates tag pose.Transform3d
estimate(AprilTagDetection detection)
Estimates tag pose.Transform3d
estimateHomography(double[] homography)
Estimates the pose of the tag using the homography method described in [1].Transform3d
estimateHomography(AprilTagDetection detection)
Estimates the pose of the tag using the homography method described in [1].AprilTagPoseEstimate
estimateOrthogonalIteration(double[] homography, double[] corners, int nIters)
Estimates the pose of the tag.AprilTagPoseEstimate
estimateOrthogonalIteration(AprilTagDetection detection, int nIters)
Estimates the pose of the tag.AprilTagPoseEstimator.Config
getConfig()
Gets estimator configuration.void
setConfig(AprilTagPoseEstimator.Config config)
Sets estimator configuration.
-
Constructor Details
-
AprilTagPoseEstimator
Creates estimator.- Parameters:
config
- Configuration
-
-
Method Details
-
setConfig
Sets estimator configuration.- Parameters:
config
- Configuration
-
getConfig
Gets estimator configuration.- Returns:
- Configuration
-
estimateHomography
Estimates the pose of the tag using the homography method described in [1].- Parameters:
detection
- Tag detection- Returns:
- Pose estimate
-
estimateHomography
Estimates the pose of the tag using the homography method described in [1].- Parameters:
homography
- Homography 3x3 matrix data- Returns:
- Pose estimate
-
estimateOrthogonalIteration
Estimates the pose of the tag. This returns one or two possible poses for the tag, along with the object-space error of each.This uses the homography method described in [1] for the initial estimate. Then Orthogonal Iteration [2] is used to refine this estimate. Then [3] is used to find a potential second local minima and Orthogonal Iteration is used to refine this second estimate.
[1]: E. Olson, “Apriltag: A robust and flexible visual fiducial system,” in 2011 IEEE International Conference on Robotics and Automation, May 2011, pp. 3400–3407.
[2]: Lu, G. D. Hager and E. Mjolsness, "Fast and globally convergent pose estimation from video images," in IEEE Transactions on Pattern Analysis and Machine Intelligence, vol. 22, no. 6, pp. 610-622, June 2000. doi: 10.1109/34.862199
[3]: Schweighofer and A. Pinz, "Robust Pose Estimation from a Planar Target," in IEEE Transactions on Pattern Analysis and Machine Intelligence, vol. 28, no. 12, pp. 2024-2030, Dec. 2006. doi: 10.1109/TPAMI.2006.252
- Parameters:
detection
- Tag detectionnIters
- Number of iterations- Returns:
- Initial and (possibly) second pose estimates
-
estimateOrthogonalIteration
public AprilTagPoseEstimate estimateOrthogonalIteration(double[] homography, double[] corners, 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)nIters
- Number of iterations- Returns:
- Initial and (possibly) second pose estimates
-
estimate
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:
detection
- Tag detection- Returns:
- Pose estimate
-
estimate
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)- Returns:
- Pose estimate
-