Package limelight.networktables
Class PoseEstimate
java.lang.Object
limelight.networktables.PoseEstimate
Represents a 3D Pose Estimate.
-
Field Summary
FieldsModifier and TypeFieldDescriptiondoubleAvg area in percent of imagedoubleAvg apriltag distance in MetersbooleanDoes the pose limelight.estimator contain data?final booleanIs a MegaTag2 readingdoubleTotal latency in secondsBot pose estimateAprilTagsintAprilTag in view countdoubleTag Span in metersdoubleNT Timestamp in seconds -
Constructor Summary
ConstructorsConstructorDescriptionPoseEstimate(Limelight camera, String entryName, boolean megaTag2) Construct thePoseEstimatefrom the limelight entry in NT. -
Method Summary
Modifier and TypeMethodDescriptiondoubleGet the average ambiguity from seen AprilTag'sdoubleGet the maximum ambiguity from seen AprilTag'sdoubleGet the minimum ambiguity from seen AprilTag'sRefreshPoseEstimateobjectrefresh()Refresh thePoseEstimatetoString()Prints detailed information about a PoseEstimate to standard output.
-
Field Details
-
isMegaTag2
public final boolean isMegaTag2Is a MegaTag2 reading -
pose
Bot pose estimate -
timestampSeconds
public double timestampSecondsNT Timestamp in seconds -
latency
public double latencyTotal latency in seconds -
tagCount
public int tagCountAprilTag in view count -
tagSpan
public double tagSpanTag Span in meters -
avgTagDist
public double avgTagDistAvg apriltag distance in Meters -
avgTagArea
public double avgTagAreaAvg area in percent of image -
rawFiducials
AprilTags -
hasData
public boolean hasDataDoes the pose limelight.estimator contain data?
-
-
Constructor Details
-
PoseEstimate
Construct thePoseEstimatefrom the limelight entry in NT.- Parameters:
camera-Limelightto fetch the data from.entryName- Pose estimation entry we are interested in.megaTag2- Is the data MegaTag2
-
-
Method Details
-
refresh
Refresh thePoseEstimate- Returns:
PoseEstimate
-
getPoseEstimate
RefreshPoseEstimateobject- Returns:
PoseEstimatefor chaining.
-
getMinTagAmbiguity
public double getMinTagAmbiguity()Get the minimum ambiguity from seen AprilTag's- Returns:
- Min ambiguity from observed tags.
-
getMaxTagAmbiguity
public double getMaxTagAmbiguity()Get the maximum ambiguity from seen AprilTag's- Returns:
- Max ambiguity from observed tags. Returns 1 if none.
-
getAvgTagAmbiguity
public double getAvgTagAmbiguity()Get the average ambiguity from seen AprilTag's- Returns:
- Avg ambiguity from observed tags. Returns 1 if no tags.
-
toString
Prints detailed information about a PoseEstimate to standard output. Includes timestamp, latency, tag count, tag span, average tag distance, average tag area, and detailed information about each detected fiducial.
-