Class SimPhotonCamera

java.lang.Object
org.photonvision.simulation.SimPhotonCamera

@Deprecated public class SimPhotonCamera extends Object
Deprecated.
Use PhotonCameraSim instead
  • Constructor Details

    • SimPhotonCamera

      public SimPhotonCamera(edu.wpi.first.networktables.NetworkTableInstance instance, String cameraName)
      Deprecated.
      Constructs a Simulated PhotonCamera from a root table.
      Parameters:
      instance - The NetworkTableInstance to pull data from. This can be a custom instance in simulation, but should *usually* be the default NTInstance from NetworkTableInstance::getDefault
      cameraName - The name of the camera, as seen in the UI.
    • SimPhotonCamera

      public SimPhotonCamera(String cameraName)
      Deprecated.
      Constructs a Simulated PhotonCamera from the name of the camera.
      Parameters:
      cameraName - The nickname of the camera (found in the PhotonVision UI).
  • Method Details

    • setCameraIntrinsicsMat

      public void setCameraIntrinsicsMat(edu.wpi.first.math.Matrix<edu.wpi.first.math.numbers.N3,edu.wpi.first.math.numbers.N3> cameraMatrix)
      Deprecated.
      Publishes the camera intrinsics matrix. The matrix should be in the form: spotless:off fx 0 cx 0 fy cy 0 0 1
      Parameters:
      cameraMatrix - The cam matrix spotless:on
    • setCameraDistortionMat

      public void setCameraDistortionMat(edu.wpi.first.math.Matrix<edu.wpi.first.math.numbers.N5,edu.wpi.first.math.numbers.N1> distortionMat)
      Deprecated.
      Publishes the camera distortion matrix. The matrix should be in the form [k1 k2 p1 p2 k3]. See more: https://docs.opencv.org/3.4/d4/d94/tutorial_camera_calibration.html
      Parameters:
      distortionMat - The distortion mat
    • submitProcessedFrame

      public void submitProcessedFrame(double latencyMillis, PhotonTrackedTarget... targets)
      Deprecated.
      Simulate one processed frame of vision data, putting one result to NT.
      Parameters:
      latencyMillis - Latency of the provided frame
      targets - Each target detected
    • submitProcessedFrame

      public void submitProcessedFrame(double latencyMillis, PhotonTargetSortMode sortMode, PhotonTrackedTarget... targets)
      Deprecated.
      Simulate one processed frame of vision data, putting one result to NT.
      Parameters:
      latencyMillis - Latency of the provided frame
      sortMode - Order in which to sort targets
      targets - Each target detected
    • submitProcessedFrame

      public void submitProcessedFrame(double latencyMillis, List<PhotonTrackedTarget> targetList)
      Deprecated.
      Simulate one processed frame of vision data, putting one result to NT.
      Parameters:
      latencyMillis - Latency of the provided frame
      targetList - List of targets detected
    • submitProcessedFrame

      public void submitProcessedFrame(double latencyMillis, PhotonTargetSortMode sortMode, List<PhotonTrackedTarget> targetList)
      Deprecated.
      Simulate one processed frame of vision data, putting one result to NT.
      Parameters:
      latencyMillis - Latency of the provided frame
      sortMode - Order in which to sort targets
      targetList - List of targets detected