- -
- -

Class NAR_Camera

-
-
java.lang.Object -
org.photonvision.PhotonCamera -
common.hardware.camera.NAR_Camera
-
-
-
-
-
All Implemented Interfaces:
-
AutoCloseable
-
-
-
public class NAR_Camera -extends org.photonvision.PhotonCamera
-
Team 3128's streamlined PhotonCamera class that provides additional functionality and ease of use. -

Geometry: https://docs.wpilib.org/en/stable/docs/software/advanced-controls/geometry/index.html. -

Photonvision: https://docs.photonvision.org/en/latest/.

-
-
Since:
-
2023 Charged Up
-
-
-
-
    - -
  • -
    -

    Field Summary

    -
    Fields
    -
    -
    Modifier and Type
    -
    Field
    -
    Description
    -
    final Camera
    - -
     
    -
    -
    -

    Fields inherited from class org.photonvision.PhotonCamera

    -kTableName
    -
    -
  • - -
  • -
    -

    Constructor Summary

    -
    Constructors
    -
    -
    Constructor
    -
    Description
    - -
    -
    Creates a NAR_Camera object.
    -
    -
    -
    -
  • - -
  • -
    -

    Method Summary

    -
    -
    -
    -
    -
    Modifier and Type
    -
    Method
    -
    Description
    -
    void
    - -
    -
    Stops the camera from updating robot odometry.
    -
    -
    void
    - -
    -
    Allows the camera to update robot odometry.
    -
    -
    edu.wpi.first.math.geometry.Transform2d
    - -
    -
    Returns the best target to camera vector as a Transform2d.
    -
    -
    double
    - -
    -
    Returns the distance from the best target to the camera.
    -
    - - -
     
    -
    edu.wpi.first.math.geometry.Pose2d
    - -
    -
    Returns position of the robot on the field based on the best target.
    -
    -
    edu.wpi.first.math.geometry.Transform2d
    - -
    -
    Returns the best target to camera vector as a Transform2d.
    -
    -
    edu.wpi.first.math.geometry.Transform3d
    - -
    -
    Returns the best target to camera vector as a Transform3d.
    -
    -
    boolean
    - -
    -
    Returns whether or not the camera sees a target.
    -
    -
    static void
    -
    setResources(DoubleSupplier gyro, - BiConsumer<edu.wpi.first.math.geometry.Pose2d,Double> odometry, - HashMap<Integer,edu.wpi.first.math.geometry.Pose2d> aprilTags, - Supplier<edu.wpi.first.math.geometry.Pose2d> poseSupplier)
    -
    -
    Sets the necessary resources for cameras to function.
    -
    -
    static void
    -
    setThresholds(double angleThreshold, - double distanceThreshold, - double ambiguityThreshold, - boolean multipleTargets)
    -
    -
    Sets the thresholds for camera pose estimates.
    -
    -
    double
    - -
    -
    Returns the ambiguity of the best target with lower being more accurate.
    -
    -
    int
    - -
    -
    Returns the ID of the best target.
    -
    -
    void
    - -
    -
    Gets the latest targets.
    -
    -
    -
    -
    -
    -

    Methods inherited from class org.photonvision.PhotonCamera

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

    Methods inherited from class java.lang.Object

    -clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
    -
    -
  • -
-
-
-
    - -
  • -
    -

    Field Details

    -
      -
    • -
      -

      camera

      -
      public final Camera camera
      -
      -
    • -
    -
    -
  • - -
  • -
    -

    Constructor Details

    -
      -
    • -
      -

      NAR_Camera

      -
      public NAR_Camera(Camera camera)
      -
      Creates a NAR_Camera object.
      -
      -
      Parameters:
      -
      camera - Specs of the camera.
      -
      -
      -
    • -
    -
    -
  • - -
  • -
    -

    Method Details

    -
      -
    • -
      -

      setResources

      -
      public static void setResources(DoubleSupplier gyro, - BiConsumer<edu.wpi.first.math.geometry.Pose2d,Double> odometry, - HashMap<Integer,edu.wpi.first.math.geometry.Pose2d> aprilTags, - Supplier<edu.wpi.first.math.geometry.Pose2d> poseSupplier)
      -
      Sets the necessary resources for cameras to function.
      -
      -
      Parameters:
      -
      gyro - Feeds the angle of the robot.
      -
      odometry - Feeds the robot odometry object for vision estimates to update.
      -
      aprilTags - Sets the AprilTag positions on the field.
      -
      poseSupplier - Supplies the robot's current pose.
      -
      -
      -
    • -
    • -
      -

      setThresholds

      -
      public static void setThresholds(double angleThreshold, - double distanceThreshold, - double ambiguityThreshold, - boolean multipleTargets)
      -
      Sets the thresholds for camera pose estimates. -

      Defaults: 30 degrees, 5 meters, 0.5, false.

      -
      -
      Parameters:
      -
      angleThreshold - Angle offset to stop using estimates.
      -
      distanceThreshold - Distance to stop accepting updates.
      -
      ambiguityThreshold - Pose ambiguity from 0.0 to 1.0 to reject estimates.
      -
      multipleTargets - Update position using multiple tags.
      -
      -
      -
    • -
    • -
      -

      enable

      -
      public void enable()
      -
      Allows the camera to update robot odometry.
      -
      -
    • -
    • -
      -

      disable

      -
      public void disable()
      -
      Stops the camera from updating robot odometry.
      -
      -
    • -
    • -
      -

      update

      -
      public void update()
      -
      Gets the latest targets.
      -
      -
    • -
    • -
      -

      hasTarget

      -
      public boolean hasTarget()
      -
      Returns whether or not the camera sees a target.
      -
      -
      Returns:
      -
      If camera sees any targets.
      -
      -
      -
    • -
    • -
      -

      getDistance

      -
      public double getDistance()
      -
      Returns the distance from the best target to the camera.
      -
      -
      Returns:
      -
      The distance in meters.
      -
      -
      -
    • -
    • -
      -

      targetId

      -
      public int targetId()
      -
      Returns the ID of the best target.
      -
      -
      Returns:
      -
      The target ID as an integer.
      -
      -
      -
    • -
    • -
      -

      targetAmbiguity

      -
      public double targetAmbiguity()
      -
      Returns the ambiguity of the best target with lower being more accurate.
      -
      -
      Returns:
      -
      A value from 0.0 to 1.0 representing the accuracy of the target.
      -
      -
      -
    • -
    • -
      -

      getTarget3d

      -
      public edu.wpi.first.math.geometry.Transform3d getTarget3d()
      -
      Returns the best target to camera vector as a Transform3d.
      -
      -
      Returns:
      -
      Transform3d with coordinate system relative to camera.
      -
      -
      -
    • -
    • -
      -

      getRelTarget

      -
      public edu.wpi.first.math.geometry.Transform2d getRelTarget()
      -
      Returns the best target to camera vector as a Transform2d. -

      - Factors in camera pitch offset.

      -
      -
      Returns:
      -
      Transform2d with coordinate system relative to camera.
      -
      -
      -
    • -
    • -
      -

      getAccTarget

      -
      public edu.wpi.first.math.geometry.Transform2d getAccTarget()
      -
      Returns the best target to camera vector as a Transform2d.
      -
      -
      Returns:
      -
      Transform2d with coordinate system relative to target.
      -
      -
      -
    • -
    • -
      -

      getPos

      -
      public edu.wpi.first.math.geometry.Pose2d getPos()
      -
      Returns position of the robot on the field based on the best target.
      -
      -
      Returns:
      -
      Pose estimate.
      -
      -
      -
    • -
    • -
      -

      getName

      -
      public String getName()
      -
      -
      Overrides:
      -
      getName in class org.photonvision.PhotonCamera
      -
      Returns:
      -
      The name of the camera.
      -
      -
      -
    • -
    -
    -
  • -
-
- -