Package limelight.networktables
Class LimelightResults
java.lang.Object
limelight.networktables.LimelightResults
-
Field Summary
FieldsModifier and TypeFieldDescriptiondouble[]Botpose (MegaTag): x,y,z, roll, pitch, yaw (meters, degrees)doubleAverage area of tags used to compute botposedoubleMax distance between tags used to compute botpose (meters)doubleMax distance between tags used to compute botpose (meters)doubleNumber of tags used to compute botposedouble[]Botpose (MegaTag, WPI Blue driverstation): x,y,z, roll, pitch, yaw (meters, degrees)double[]Botpose (MegaTag, WPI Red driverstation): x,y,z, roll, pitch, yaw (meters, degrees)double[]Error message, if any.doubleCapture latency (milliseconds between the end of the exposure of the middle row to the beginning of the tracking loop)doubledoubleTargeting latency (milliseconds consumed by tracking loop this frame)doubleCurrent pipeline indexBarcode[]Barcode pipeline results arrayClassifier pipeline results arrayNeural Detector pipeline results arrayAprilTag pipeline results arrayColor/Retroreflective pipeline results arraydoubleTimestamp in milliseconds from boot.doublebooleanValidity indicator. -
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionGet the current botpose as aPose2dobject.getBotPose2d(DriverStation.Alliance alliance) Get the current botpose as aPose2dobject.Get the current botpose as aPose3dobject.getBotPose3d(DriverStation.Alliance alliance) Get the current botpose as aPose3dobject.toString()Commonly used but very incomplete set from JSON key from the LL
-
Field Details
-
error
Error message, if any. -
pipelineID
public double pipelineIDCurrent pipeline index -
latency_pipeline
public double latency_pipelineTargeting latency (milliseconds consumed by tracking loop this frame) -
latency_capture
public double latency_captureCapture latency (milliseconds between the end of the exposure of the middle row to the beginning of the tracking loop) -
latency_jsonParse
public double latency_jsonParse -
timestamp_LIMELIGHT_publish
public double timestamp_LIMELIGHT_publishTimestamp in milliseconds from boot. -
timestamp_RIOFPGA_capture
public double timestamp_RIOFPGA_capture -
valid
public boolean validValidity indicator. 1 = valid targets, 0 = no valid targets -
botpose
public double[] botposeBotpose (MegaTag): x,y,z, roll, pitch, yaw (meters, degrees) -
botpose_wpired
public double[] botpose_wpiredBotpose (MegaTag, WPI Red driverstation): x,y,z, roll, pitch, yaw (meters, degrees) -
botpose_wpiblue
public double[] botpose_wpiblueBotpose (MegaTag, WPI Blue driverstation): x,y,z, roll, pitch, yaw (meters, degrees) -
botpose_tagcount
public double botpose_tagcountNumber of tags used to compute botpose -
botpose_span
public double botpose_spanMax distance between tags used to compute botpose (meters) -
botpose_avgdist
public double botpose_avgdistMax distance between tags used to compute botpose (meters) -
botpose_avgarea
public double botpose_avgareaAverage area of tags used to compute botpose -
camerapose_robotspace
public double[] camerapose_robotspace -
targets_Retro
Color/Retroreflective pipeline results array -
targets_Fiducials
AprilTag pipeline results array -
targets_Classifier
Classifier pipeline results array -
targets_Detector
Neural Detector pipeline results array -
targets_Barcode
Barcode pipeline results array
-
-
Constructor Details
-
LimelightResults
public LimelightResults()Construct a LimelightResults object for JSON Parsing.
-
-
Method Details
-
getBotPose3d
Get the current botpose as aPose3dobject.- Returns:
Pose3dobject representing the botpose.
-
getBotPose3d
Get the current botpose as aPose3dobject.- Parameters:
alliance- Alliance color to get the botpose for.- Returns:
Pose3dobject representing the botpose.
-
getBotPose2d
Get the current botpose as aPose2dobject.- Returns:
Pose2dobject representing the botpose.
-
getBotPose2d
Get the current botpose as aPose2dobject.- Parameters:
alliance- Alliance color to get the botpose for.- Returns:
Pose2dobject representing the botpose.
-
toString
Commonly used but very incomplete set from JSON key from the LL
-