WPILibC++ 2024.3.2
|
Pose estimators for AprilTag tags. More...
#include <frc/apriltag/AprilTagPoseEstimator.h>
Classes | |
struct | Config |
Configuration for the pose estimator. More... | |
Public Member Functions | |
AprilTagPoseEstimator (const Config &config) | |
Creates estimator. More... | |
void | SetConfig (const Config &config) |
Sets estimator configuration. More... | |
const Config & | GetConfig () const |
Gets estimator configuration. More... | |
Transform3d | EstimateHomography (const AprilTagDetection &detection) const |
Estimates the pose of the tag using the homography method described in [1]. More... | |
Transform3d | EstimateHomography (std::span< const double, 9 > homography) const |
Estimates the pose of the tag using the homography method described in [1]. More... | |
AprilTagPoseEstimate | EstimateOrthogonalIteration (const AprilTagDetection &detection, int nIters) const |
Estimates the pose of the tag. More... | |
AprilTagPoseEstimate | EstimateOrthogonalIteration (std::span< const double, 9 > homography, std::span< const double, 8 > corners, int nIters) const |
Estimates the pose of the tag. More... | |
Transform3d | Estimate (const AprilTagDetection &detection) const |
Estimates tag pose. More... | |
Transform3d | Estimate (std::span< const double, 9 > homography, std::span< const double, 8 > corners) const |
Estimates tag pose. More... | |
Pose estimators for AprilTag tags.
|
inlineexplicit |
Creates estimator.
config | Configuration |
Transform3d frc::AprilTagPoseEstimator::Estimate | ( | const AprilTagDetection & | detection | ) | const |
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.
detection | Tag detection |
Transform3d frc::AprilTagPoseEstimator::Estimate | ( | std::span< const double, 9 > | homography, |
std::span< const double, 8 > | corners | ||
) | const |
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.
homography | Homography 3x3 matrix data |
corners | Corner point array (X and Y for each corner in order) |
Transform3d frc::AprilTagPoseEstimator::EstimateHomography | ( | const AprilTagDetection & | detection | ) | const |
Estimates the pose of the tag using the homography method described in [1].
detection | Tag detection |
Transform3d frc::AprilTagPoseEstimator::EstimateHomography | ( | std::span< const double, 9 > | homography | ) | const |
Estimates the pose of the tag using the homography method described in [1].
homography | Homography 3x3 matrix data |
AprilTagPoseEstimate frc::AprilTagPoseEstimator::EstimateOrthogonalIteration | ( | const AprilTagDetection & | detection, |
int | nIters | ||
) | const |
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
detection | Tag detection |
nIters | Number of iterations |
AprilTagPoseEstimate frc::AprilTagPoseEstimator::EstimateOrthogonalIteration | ( | std::span< const double, 9 > | homography, |
std::span< const double, 8 > | corners, | ||
int | nIters | ||
) | const |
Estimates the pose of the tag.
This returns one or two possible poses for the tag, along with the object-space error of each.
homography | Homography 3x3 matrix data |
corners | Corner point array (X and Y for each corner in order) |
nIters | Number of iterations |
|
inline |
Gets estimator configuration.
|
inline |
Sets estimator configuration.
config | Configuration |