Package frclib.vision

Class FrcPhotonVision

java.lang.Object
org.photonvision.PhotonCamera
frclib.vision.FrcPhotonVision
All Implemented Interfaces:
AutoCloseable

public abstract class FrcPhotonVision extends org.photonvision.PhotonCamera
This class implements vision detection using PhotonLib extending PhotonCamera.
  • Nested Class Summary

    Nested Classes
    Modifier and Type
    Class
    Description
    class 
    This class encapsulates info of the detected object.
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    protected final String
     
    protected final TrcDbgTrace
     

    Fields inherited from class org.photonvision.PhotonCamera

    kTableName
  • Constructor Summary

    Constructors
    Constructor
    Description
    FrcPhotonVision(String cameraName, edu.wpi.first.math.geometry.Transform3d robotToCamera)
    Constructor: Create an instance of the object.
  • Method Summary

    Modifier and Type
    Method
    Description
    This method returns the best detected object.
    getDetectedAprilTag(int aprilTagId)
    This method returns the detected AprilTag object.
    This method returns the array of detected objects.
    getRobotEstimatedPose(edu.wpi.first.math.geometry.Transform3d robotToCamera)
    This method uses the PhotonVision Pose Estimator to get an estimated absolute field position of the robot.
    getRobotEstimatedPose(org.photonvision.targeting.PhotonPipelineResult result, edu.wpi.first.math.geometry.Transform3d robotToCamera)
    This method uses the PhotonVision Pose Estimator to get an estimated absolute field position of the robot.
    getRobotPoseFromAprilTagFieldPose(edu.wpi.first.math.geometry.Pose3d aprilTagFieldPose3d, edu.wpi.first.math.geometry.Transform3d cameraToTarget, edu.wpi.first.math.geometry.Transform3d robotToCamera)
    This method calculates the robot's field position by subtracting the AprilTag's field position by the AprilTag position from the camera and the camera position on the robot.
    abstract double
    getTargetGroundOffset(org.photonvision.targeting.PhotonTrackedTarget target)
    This method is provided by the subclass to provide the target offset from ground so that vision can accurately calculate the target position from the camera.
    getTargetPoseOffsetFromAprilTag(edu.wpi.first.math.geometry.Pose3d aprilTagFieldPose3d, double xOffset, double yOffset, double angleOffset)
    This method calculates the target pose with an offset from the given AprilTag pose.
    void
    This method prints the performance metrics to the trace log.
    void
    This method enables/disables performance metrics.
    This method returns the photon camera name.

    Methods inherited from class org.photonvision.PhotonCamera

    close, getAllUnreadResults, getCameraMatrix, getCameraTable, getDistCoeffs, getDriverMode, getLatestResult, getLEDMode, getName, getPipelineIndex, isConnected, setDriverMode, setLED, setPipelineIndex, setVersionCheckEnabled, takeInputSnapshot, takeOutputSnapshot

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, wait, wait, wait
  • Field Details

    • tracer

      protected final TrcDbgTrace tracer
    • instanceName

      protected final String instanceName
  • Constructor Details

    • FrcPhotonVision

      public FrcPhotonVision(String cameraName, edu.wpi.first.math.geometry.Transform3d robotToCamera)
      Constructor: Create an instance of the object.
      Parameters:
      cameraName - specifies the network table name that PhotonVision is broadcasting information over.
      robotToCamera - specifies the Transform3d of the camera position on the robot.
  • Method Details

    • getTargetGroundOffset

      public abstract double getTargetGroundOffset(org.photonvision.targeting.PhotonTrackedTarget target)
      This method is provided by the subclass to provide the target offset from ground so that vision can accurately calculate the target position from the camera.
      Parameters:
      target - specifies the photon detected target.
      Returns:
      target ground offset in inches.
    • toString

      public String toString()
      This method returns the photon camera name.
      Overrides:
      toString in class Object
      Returns:
      photon camera name.
    • setPerformanceMetricsEnabled

      public void setPerformanceMetricsEnabled(boolean enabled)
      This method enables/disables performance metrics.
      Parameters:
      enabled - specifies true to enable performance metrics, false to disable.
    • printPerformanceMetrics

      public void printPerformanceMetrics()
      This method prints the performance metrics to the trace log.
    • getDetectedObjects

      public FrcPhotonVision.DetectedObject[] getDetectedObjects()
      This method returns the array of detected objects.
      Returns:
      array of detected objects.
    • getBestDetectedObject

      public FrcPhotonVision.DetectedObject getBestDetectedObject()
      This method returns the best detected object.
      Returns:
      best detected object.
    • getDetectedAprilTag

      public FrcPhotonVision.DetectedObject getDetectedAprilTag(int aprilTagId)
      This method returns the detected AprilTag object.
      Parameters:
      aprilTagId - specifies the AprilTag ID to look for, -1 if looking for any AprilTag.
      Returns:
      detected AprilTag object.
    • getRobotEstimatedPose

      public TrcPose2D getRobotEstimatedPose(org.photonvision.targeting.PhotonPipelineResult result, edu.wpi.first.math.geometry.Transform3d robotToCamera)
      This method uses the PhotonVision Pose Estimator to get an estimated absolute field position of the robot.
      Parameters:
      result - specifies the latest pipeline result.
      robotToCamera - specifies the Transform3d position of the camera from the robot center.
      Returns:
      absolute robot field position, can be null if not provided.
    • getRobotEstimatedPose

      public TrcPose2D getRobotEstimatedPose(edu.wpi.first.math.geometry.Transform3d robotToCamera)
      This method uses the PhotonVision Pose Estimator to get an estimated absolute field position of the robot.
      Parameters:
      robotToCamera - specifies the Transform3d position of the camera from the robot center.
      Returns:
      absolute robot field position, can be null if not provided.
    • getRobotPoseFromAprilTagFieldPose

      public TrcPose2D getRobotPoseFromAprilTagFieldPose(edu.wpi.first.math.geometry.Pose3d aprilTagFieldPose3d, edu.wpi.first.math.geometry.Transform3d cameraToTarget, edu.wpi.first.math.geometry.Transform3d robotToCamera)
      This method calculates the robot's field position by subtracting the AprilTag's field position by the AprilTag position from the camera and the camera position on the robot.
      Parameters:
      aprilTagFieldPose - specifies the AprilTag's field position.
      aprilTagTargetPose - specifies the AprilTag's position from the camera.
      robotToCamera - specifies the camera's position on the robot.
      Returns:
      robot's field position.
    • getTargetPoseOffsetFromAprilTag

      public TrcPose2D getTargetPoseOffsetFromAprilTag(edu.wpi.first.math.geometry.Pose3d aprilTagFieldPose3d, double xOffset, double yOffset, double angleOffset)
      This method calculates the target pose with an offset from the given AprilTag pose.
      Parameters:
      aprilTagFieldPose3d - specifies the AprilTag 3D field pose.
      xOffset - specifies the x-offset from AprilTag in inches.
      yOffset - specifies the y-offset from AprilTag in inches.
      angleOffset - specifies the angle offset in degrees.
      Returns:
      calculated target pose.