Class PipelineResult

java.lang.Object
io.github.roboblazers7617.limelight.PipelineResult

public class PipelineResult extends Object
Limelight PipelineResult object, parsed from a Limelight's JSON results output.
  • Field Details

    • error

      public String error
      Error output from the JSON parser.
    • pipelineID

      public double pipelineID
      The current Pipeline's index.
    • latency_pipeline

      public double latency_pipeline
      The targeting latency (milliseconds consumed by tracking loop this frame).
    • latency_capture

      public double latency_capture
      The capture 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
      The latency introduced by parsing the JSON file.
    • timestamp_LIMELIGHT_publish

      public double timestamp_LIMELIGHT_publish
      Timestamp in milliseconds from Limelight boot.
    • timestamp_RIOFPGA_capture

      public double timestamp_RIOFPGA_capture
    • valid

      public boolean valid
      Are there valid targets in this result?
    • botpose

      public double[] botpose
      Botpose (MegaTag).
      API Note:
      Array format is [x, y, z, roll, pitch, yaw (meters, degrees)]
    • botpose_wpired

      public double[] botpose_wpired
      Botpose (MegaTag, WPI Red driverstation).
      API Note:
      Array format is [x, y, z, roll, pitch, yaw (meters, degrees)]
    • botpose_wpiblue

      public double[] botpose_wpiblue
      Botpose (MegaTag, WPI Blue driverstation).
      API Note:
      Array format is [x, y, z, roll, pitch, yaw (meters, degrees)]
    • botpose_tagcount

      public double botpose_tagcount
      The number of tags used to compute the botpose.
    • botpose_span

      public double botpose_span
      The maximum distance between tags used to compute the botpose in meters.
    • botpose_avgdist

      public double botpose_avgdist
      The average distance between tags used to compute the botpose in meters.
    • botpose_avgarea

      public double botpose_avgarea
      The average area of the tags used to compute the botpose.
    • camerapose_robotspace

      public double[] camerapose_robotspace
    • targets_Retro

      public RetroreflectiveTarget[] targets_Retro
      Retroreflective pipeline outputs.
    • targets_Fiducials

      public FiducialTarget[] targets_Fiducials
      Fiducial target pipeline outputs.
    • targets_Classifier

      public ClassifierTarget[] targets_Classifier
      Classifier pipeline outputs.
    • targets_Detector

      public DetectorTarget[] targets_Detector
      Neural Detector pipeline outputs.
    • targets_Barcode

      public BarcodeTarget[] targets_Barcode
      Barcode pipeline outputs.
    • standardDeviations_MegaTag1

      public double[] standardDeviations_MegaTag1
      MegaTag1 Standard Deviation.
      API Note:
      Array format is [x, y, z, roll, pitch, yaw] (meters, degrees).
    • standardDeviations_MegaTag2

      public double[] standardDeviations_MegaTag2
      MegaTag2 Standard Deviation.
      API Note:
      Array format is [x, y, z, roll, pitch, yaw] (meters, degrees).
  • Constructor Details

    • PipelineResult

      public PipelineResult()
      Creates a new PipelineResult with blank values.
  • Method Details