Class AprilTagFiducial

java.lang.Object
limelight.networktables.target.AprilTagFiducial

public class AprilTagFiducial extends Object
Represents an AprilTag/Fiducial Target Result extracted from JSON Output
  • Field Details

    • fiducialID

      public double fiducialID
      Fiducial tag ID
    • fiducialFamily

      public String fiducialFamily
      Fiducial Family (16H5C, 25H9C, 36H11C, etc)
    • 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

    • AprilTagFiducial

      public AprilTagFiducial()
      Create the AprilTagFiducial object
  • Method Details

    • getCameraPose_TargetSpace

      public Pose3d getCameraPose_TargetSpace()
      Get the AprilTag's 3D pose in target space
      Returns:
      Pose3d object representing the AprilTag's position and orientation relative to the camera
    • getRobotPose_FieldSpace

      public Pose3d getRobotPose_FieldSpace()
      Get the AprilTag's 3D pose in field space
      Returns:
      Pose3d object representing the AprilTag's position and orientation relative to the robot
    • getRobotPose_TargetSpace

      public Pose3d getRobotPose_TargetSpace()
      Get the AprilTag's 3D pose in target space
      Returns:
      Pose3d object representing the AprilTag's position and orientation relative to the robot
    • getTargetPose_CameraSpace

      public Pose3d getTargetPose_CameraSpace()
      Get the AprilTag's 3D pose in camera space
      Returns:
      Pose3d object representing the AprilTag's position and orientation relative to the camera
    • getTargetPose_RobotSpace

      public Pose3d getTargetPose_RobotSpace()
      Get the AprilTag's 3D pose in robot space
      Returns:
      Pose3d object representing the AprilTag's position and orientation relative to the robot
    • getCameraPose_TargetSpace2D

      public Pose2d getCameraPose_TargetSpace2D()
      Get the AprilTag's 2D pose in target space
      Returns:
      Pose2d object representing the AprilTag's position and orientation relative to the camera
    • getRobotPose_FieldSpace2D

      public Pose2d getRobotPose_FieldSpace2D()
      Get the AprilTag's 2D pose in field space
      Returns:
      Pose2d object representing the AprilTag's position and orientation relative to the robot
    • getRobotPose_TargetSpace2D

      public Pose2d getRobotPose_TargetSpace2D()
      Get the AprilTag's 2D pose in target space
      Returns:
      Pose2d object representing the AprilTag's position and orientation relative to the robot
    • getTargetPose_CameraSpace2D

      public Pose2d getTargetPose_CameraSpace2D()
      Get the AprilTag's 2D pose in camera space
      Returns:
      Pose2d object representing the AprilTag's position and orientation relative to the camera
    • getTargetPose_RobotSpace2D

      public Pose2d getTargetPose_RobotSpace2D()
      Get the AprilTag's 2D pose in robot space
      Returns:
      Pose2d object representing the AprilTag's position and orientation relative to the robot