Package org.photonvision.estimation
Class VisionEstimation
java.lang.Object
org.photonvision.estimation.VisionEstimation
-
Constructor Summary
-
Method Summary
Modifier and TypeMethodDescriptionstatic PNPResult
estimateCamPosePNP
(edu.wpi.first.math.Matrix<edu.wpi.first.math.numbers.N3, edu.wpi.first.math.numbers.N3> cameraMatrix, edu.wpi.first.math.Matrix<edu.wpi.first.math.numbers.N5, edu.wpi.first.math.numbers.N1> distCoeffs, List<PhotonTrackedTarget> visTags, edu.wpi.first.apriltag.AprilTagFieldLayout tagLayout, TargetModel tagModel) Performs solvePNP using 3d-2d point correspondences of visible AprilTags to estimate the field-to-camera transformation.static List<edu.wpi.first.apriltag.AprilTag>
getVisibleLayoutTags
(List<PhotonTrackedTarget> visTags, edu.wpi.first.apriltag.AprilTagFieldLayout tagLayout) Get the visibleAprilTag
s which are in the tag layout using the visible tag IDs.
-
Constructor Details
-
VisionEstimation
public VisionEstimation()
-
-
Method Details
-
getVisibleLayoutTags
public static List<edu.wpi.first.apriltag.AprilTag> getVisibleLayoutTags(List<PhotonTrackedTarget> visTags, edu.wpi.first.apriltag.AprilTagFieldLayout tagLayout) Get the visibleAprilTag
s which are in the tag layout using the visible tag IDs. -
estimateCamPosePNP
public static PNPResult estimateCamPosePNP(edu.wpi.first.math.Matrix<edu.wpi.first.math.numbers.N3, edu.wpi.first.math.numbers.N3> cameraMatrix, edu.wpi.first.math.Matrix<edu.wpi.first.math.numbers.N5, edu.wpi.first.math.numbers.N1> distCoeffs, List<PhotonTrackedTarget> visTags, edu.wpi.first.apriltag.AprilTagFieldLayout tagLayout, TargetModel tagModel) Performs solvePNP using 3d-2d point correspondences of visible AprilTags to estimate the field-to-camera transformation. If only one tag is visible, the result may have an alternate solution.Note: The returned transformation is from the field origin to the camera pose!
- Parameters:
cameraMatrix
- The camera intrinsics matrix in standard opencv formdistCoeffs
- The camera distortion matrix in standard opencv formvisTags
- The visible tags reported by PV. Non-tag targets are automatically excluded.tagLayout
- The known tag layout on the field- Returns:
- The transformation that maps the field origin to the camera pose. Ensure the
PNPResult
are present before utilizing them.
-