Class VisionSystemSim

java.lang.Object
org.photonvision.simulation.VisionSystemSim

public class VisionSystemSim extends Object
A simulated vision system involving a camera(s) and coprocessor(s) mounted on a mobile robot running PhotonVision, detecting targets placed on the field. VisionTargetSims added to this class will be detected by the PhotonCameraSims added to this class. This class should be updated periodically with the robot's current pose in order to publish the simulated camera target info.
  • Constructor Details

    • VisionSystemSim

      public VisionSystemSim(String visionSystemName)
      A simulated vision system involving a camera(s) and coprocessor(s) mounted on a mobile robot running PhotonVision, detecting targets placed on the field. VisionTargetSims added to this class will be detected by the PhotonCameraSims added to this class. This class should be updated periodically with the robot's current pose in order to publish the simulated camera target info.
      Parameters:
      visionSystemName - The specific identifier for this vision system in NetworkTables.
  • Method Details

    • getCameraSim

      public Optional<PhotonCameraSim> getCameraSim(String name)
      Get one of the simulated cameras.
    • getCameraSims

      public Collection<PhotonCameraSim> getCameraSims()
      Get all the simulated cameras.
    • addCamera

      public void addCamera(PhotonCameraSim cameraSim, edu.wpi.first.math.geometry.Transform3d robotToCamera)
      Adds a simulated camera to this vision system with a specified robot-to-camera transformation. The vision targets registered with this vision system simulation will be observed by the simulated PhotonCamera.
      Parameters:
      cameraSim - The camera simulation
      robotToCamera - The transform from the robot pose to the camera pose
    • clearCameras

      public void clearCameras()
      Remove all simulated cameras from this vision system.
    • removeCamera

      public boolean removeCamera(PhotonCameraSim cameraSim)
      Remove a simulated camera from this vision system.
      Returns:
      If the camera was present and removed
    • getRobotToCamera

      public Optional<edu.wpi.first.math.geometry.Transform3d> getRobotToCamera(PhotonCameraSim cameraSim)
      Get a simulated camera's position relative to the robot. If the requested camera is invalid, an empty optional is returned.
      Parameters:
      cameraSim - The specific camera to get the robot-to-camera transform of
      Returns:
      The transform of this camera, or an empty optional if it is invalid
    • getRobotToCamera

      public Optional<edu.wpi.first.math.geometry.Transform3d> getRobotToCamera(PhotonCameraSim cameraSim, double timeSeconds)
      Get a simulated camera's position relative to the robot. If the requested camera is invalid, an empty optional is returned.
      Parameters:
      cameraSim - The specific camera to get the robot-to-camera transform of
      timeSeconds - Timestamp in seconds of when the transform should be observed
      Returns:
      The transform of this camera, or an empty optional if it is invalid
    • getCameraPose

      public Optional<edu.wpi.first.math.geometry.Pose3d> getCameraPose(PhotonCameraSim cameraSim)
      Get a simulated camera's position on the field. If the requested camera is invalid, an empty optional is returned.
      Parameters:
      cameraSim - The specific camera to get the field pose of
      Returns:
      The pose of this camera, or an empty optional if it is invalid
    • getCameraPose

      public Optional<edu.wpi.first.math.geometry.Pose3d> getCameraPose(PhotonCameraSim cameraSim, double timeSeconds)
      Get a simulated camera's position on the field. If the requested camera is invalid, an empty optional is returned.
      Parameters:
      cameraSim - The specific camera to get the field pose of
      timeSeconds - Timestamp in seconds of when the pose should be observed
      Returns:
      The pose of this camera, or an empty optional if it is invalid
    • adjustCamera

      public boolean adjustCamera(PhotonCameraSim cameraSim, edu.wpi.first.math.geometry.Transform3d robotToCamera)
      Adjust a camera's position relative to the robot. Use this if your camera is on a gimbal or turret or some other mobile platform.
      Parameters:
      cameraSim - The simulated camera to change the relative position of
      robotToCamera - New transform from the robot to the camera
      Returns:
      If the cameraSim was valid and transform was adjusted
    • resetCameraTransforms

      public void resetCameraTransforms()
      Reset the previous transforms for all cameras to their current transform.
    • resetCameraTransforms

      public boolean resetCameraTransforms(PhotonCameraSim cameraSim)
      Reset the transform history for this camera to just the current transform.
      Returns:
      If the cameraSim was valid and transforms were reset
    • getVisionTargets

      public Set<VisionTargetSim> getVisionTargets()
    • getVisionTargets

      public Set<VisionTargetSim> getVisionTargets(String type)
    • addVisionTargets

      public void addVisionTargets(VisionTargetSim... targets)
      Adds targets on the field which your vision system is designed to detect. The PhotonCameras simulated from this system will report the location of the camera relative to the subset of these targets which are visible from the given camera position.

      By default these are added under the type "targets".

      Parameters:
      targets - Targets to add to the simulated field
    • addAprilTags

      public void addAprilTags(edu.wpi.first.apriltag.AprilTagFieldLayout tagLayout)
      Adds targets on the field which your vision system is designed to detect. The PhotonCameras simulated from this system will report the location of the camera relative to the subset of these targets which are visible from the given camera position.

      The AprilTags from this layout will be added as vision targets under the type "apriltag". The poses added preserve the tag layout's current alliance origin. If the tag layout's alliance origin is changed, these added tags will have to be cleared and re-added.

      Parameters:
      tagLayout - The field tag layout to get Apriltag poses and IDs from
    • addVisionTargets

      public void addVisionTargets(String type, VisionTargetSim... targets)
      Adds targets on the field which your vision system is designed to detect. The PhotonCameras simulated from this system will report the location of the camera relative to the subset of these targets which are visible from the given camera position.
      Parameters:
      type - Type of target (e.g. "cargo").
      targets - Targets to add to the simulated field
    • clearVisionTargets

      public void clearVisionTargets()
    • clearAprilTags

      public void clearAprilTags()
    • removeVisionTargets

      public Set<VisionTargetSim> removeVisionTargets(String type)
    • removeVisionTargets

      public Set<VisionTargetSim> removeVisionTargets(VisionTargetSim... targets)
    • getRobotPose

      public edu.wpi.first.math.geometry.Pose3d getRobotPose()
      Get the latest robot pose in meters saved by the vision system.
    • getRobotPose

      public edu.wpi.first.math.geometry.Pose3d getRobotPose(double timestamp)
      Get the robot pose in meters saved by the vision system at this timestamp.
      Parameters:
      timestamp - Timestamp of the desired robot pose
    • resetRobotPose

      public void resetRobotPose(edu.wpi.first.math.geometry.Pose2d robotPose)
      Clears all previous robot poses and sets robotPose at current time.
    • resetRobotPose

      public void resetRobotPose(edu.wpi.first.math.geometry.Pose3d robotPose)
      Clears all previous robot poses and sets robotPose at current time.
    • getDebugField

      public edu.wpi.first.wpilibj.smartdashboard.Field2d getDebugField()
    • update

      public void update(edu.wpi.first.math.geometry.Pose2d robotPoseMeters)
      Periodic update. Ensure this is called repeatedly-- camera performance is used to automatically determine if a new frame should be submitted.
      Parameters:
      robotPoseMeters - The simulated robot pose in meters
    • update

      public void update(edu.wpi.first.math.geometry.Pose3d robotPoseMeters)
      Periodic update. Ensure this is called repeatedly-- camera performance is used to automatically determine if a new frame should be submitted.
      Parameters:
      robotPoseMeters - The simulated robot pose in meters