Class RetroreflectiveTape

java.lang.Object
limelight.networktables.target.RetroreflectiveTape

public class RetroreflectiveTape extends Object
Represents a Color/Retroreflective Target Result extracted from JSON Output
  • Field Details

    • ta

      public double ta
      The size of the target as a percentage of the image (0-1)
    • tx

      public double tx
      X-coordinate of the center of the target in degrees relative to crosshair. Positive-right, center-zero
    • ty

      public double ty
      Y-coordinate of the center of the target in degrees relative to crosshair. Positive-down, center-zero
    • tx_pixels

      public double tx_pixels
      X-coordinate of the center of the target in pixels relative to crosshair. Positive-right, center-zero
    • ty_pixels

      public double ty_pixels
      Y-coordinate of the center of the target in pixels relative to crosshair. Positive-down, center-zero
    • tx_nocrosshair

      public double tx_nocrosshair
      X-coordinate of the center of the target in degrees relative to principal piexel. Positive-right, center-zero
    • ty_nocrosshair

      public double ty_nocrosshair
      Y-coordinate of the center of the target in degrees relative to principal pixel. Positive-right, center-zero
    • ts

      public double ts
      Timestamp in milliseconds from boot.
  • Constructor Details

    • RetroreflectiveTape

      public RetroreflectiveTape()
      Create the RetroreflectiveTape object
  • Method Details

    • getCameraPose_TargetSpace

      public Pose3d getCameraPose_TargetSpace()
      Get the current botpose as a Pose3d object.
      Returns:
      Pose3d object representing the botpose.
    • getRobotPose_FieldSpace

      public Pose3d getRobotPose_FieldSpace()
      Get the current botpose as a Pose3d object.
      Returns:
      Pose3d object representing the botpose.
    • getRobotPose_TargetSpace

      public Pose3d getRobotPose_TargetSpace()
      Get the current botpose as a Pose3d object.
      Returns:
      Pose3d object representing the botpose.
    • getTargetPose_CameraSpace

      public Pose3d getTargetPose_CameraSpace()
      Get the current botpose as a Pose3d object.
      Returns:
      Pose3d object representing the botpose.
    • getTargetPose_RobotSpace

      public Pose3d getTargetPose_RobotSpace()
      Get the current botpose as a Pose3d object.
      Returns:
      Pose3d object representing the botpose.
    • getCameraPose_TargetSpace2D

      public Pose2d getCameraPose_TargetSpace2D()
      Get the current botpose as a Pose2d object.
      Returns:
      Pose2d object representing the botpose.
    • getRobotPose_FieldSpace2D

      public Pose2d getRobotPose_FieldSpace2D()
      Get the current botpose as a Pose2d object.
      Returns:
      Pose2d object representing the botpose.
    • getRobotPose_TargetSpace2D

      public Pose2d getRobotPose_TargetSpace2D()
      Get the current botpose as a Pose2d object.
      Returns:
      Pose2d object representing the botpose.
    • getTargetPose_CameraSpace2D

      public Pose2d getTargetPose_CameraSpace2D()
      Get the current botpose as a Pose2d object.
      Returns:
      Pose2d object representing the botpose.
    • getTargetPose_RobotSpace2D

      public Pose2d getTargetPose_RobotSpace2D()
      Get the current botpose as a Pose2d object.
      Returns:
      Pose2d object representing the botpose.