Package edu.wpi.first.apriltag
Class AprilTagPoseEstimate
java.lang.Object
edu.wpi.first.apriltag.AprilTagPoseEstimate
public class AprilTagPoseEstimate extends Object
A pair of AprilTag pose estimates.
-
Field Summary
Fields Modifier and Type Field Description double
error1
Object-space error of pose 1.double
error2
Object-space error of pose 2.Transform3d
pose1
Pose 1.Transform3d
pose2
Pose 2. -
Constructor Summary
Constructors Constructor Description AprilTagPoseEstimate(Transform3d pose1, Transform3d pose2, double error1, double error2)
Constructs a pose estimate. -
Method Summary
Modifier and Type Method Description double
getAmbiguity()
Get the ratio of pose reprojection errors, called ambiguity.
-
Field Details
-
Constructor Details
-
AprilTagPoseEstimate
Constructs a pose estimate.- Parameters:
pose1
- first posepose2
- second poseerror1
- error of first poseerror2
- error of second pose
-
-
Method Details
-
getAmbiguity
Get the ratio of pose reprojection errors, called ambiguity. Numbers above 0.2 are likely to be ambiguous.- Returns:
- The ratio of pose reprojection errors.
-