Package org.photonvision.simulation
Class VisionSystemSim
java.lang.Object
org.photonvision.simulation.VisionSystemSim
A simulated vision system involving a camera(s) and coprocessor(s) mounted on a mobile robot
running PhotonVision, detecting targets placed on the field.
VisionTargetSim
s added to
this class will be detected by the PhotonCameraSim
s 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 Summary
ConstructorDescriptionVisionSystemSim
(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. -
Method Summary
Modifier and TypeMethodDescriptionvoid
addAprilTags
(AprilTagFieldLayout tagLayout) Adds targets on the field which your vision system is designed to detect.void
addCamera
(PhotonCameraSim cameraSim, Transform3d robotToCamera) Adds a simulated camera to this vision system with a specified robot-to-camera transformation.void
addVisionTargets
(String type, VisionTargetSim... targets) Adds targets on the field which your vision system is designed to detect.void
addVisionTargets
(VisionTargetSim... targets) Adds targets on the field which your vision system is designed to detect.boolean
adjustCamera
(PhotonCameraSim cameraSim, Transform3d robotToCamera) Adjust a camera's position relative to the robot.void
void
Remove all simulated cameras from this vision system.void
getCameraPose
(PhotonCameraSim cameraSim) Get a simulated camera's position on the field.getCameraPose
(PhotonCameraSim cameraSim, double timeSeconds) Get a simulated camera's position on the field.getCameraSim
(String name) Get one of the simulated cameras.Get all the simulated cameras.Get the latest robot pose in meters saved by the vision system.getRobotPose
(double timestamp) Get the robot pose in meters saved by the vision system at this timestamp.getRobotToCamera
(PhotonCameraSim cameraSim) Get a simulated camera's position relative to the robot.getRobotToCamera
(PhotonCameraSim cameraSim, double timeSeconds) Get a simulated camera's position relative to the robot.getVisionTargets
(String type) boolean
removeCamera
(PhotonCameraSim cameraSim) Remove a simulated camera from this vision system.removeVisionTargets
(String type) removeVisionTargets
(VisionTargetSim... targets) void
Reset the previous transforms for all cameras to their current transform.boolean
resetCameraTransforms
(PhotonCameraSim cameraSim) Reset the transform history for this camera to just the current transform.void
resetRobotPose
(Pose2d robotPose) Clears all previous robot poses and sets robotPose at current time.void
resetRobotPose
(Pose3d robotPose) Clears all previous robot poses and sets robotPose at current time.void
Periodic update.void
Periodic update.
-
Constructor Details
-
VisionSystemSim
A simulated vision system involving a camera(s) and coprocessor(s) mounted on a mobile robot running PhotonVision, detecting targets placed on the field.VisionTargetSim
s added to this class will be detected by thePhotonCameraSim
s 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
Get one of the simulated cameras. -
getCameraSims
Get all the simulated cameras. -
addCamera
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 simulatedPhotonCamera
.- Parameters:
cameraSim
- The camera simulationrobotToCamera
- The transform from the robot pose to the camera pose
-
clearCameras
public void clearCameras()Remove all simulated cameras from this vision system. -
removeCamera
Remove a simulated camera from this vision system.- Returns:
- If the camera was present and removed
-
getRobotToCamera
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
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 oftimeSeconds
- 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
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
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 oftimeSeconds
- 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
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 ofrobotToCamera
- 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
Reset the transform history for this camera to just the current transform.- Returns:
- If the cameraSim was valid and transforms were reset
-
getVisionTargets
-
getVisionTargets
-
addVisionTargets
Adds targets on the field which your vision system is designed to detect. ThePhotonCamera
s 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
Adds targets on the field which your vision system is designed to detect. ThePhotonCamera
s 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
Adds targets on the field which your vision system is designed to detect. ThePhotonCamera
s 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
-
removeVisionTargets
-
getRobotPose
Get the latest robot pose in meters saved by the vision system. -
getRobotPose
Get the robot pose in meters saved by the vision system at this timestamp.- Parameters:
timestamp
- Timestamp of the desired robot pose
-
resetRobotPose
Clears all previous robot poses and sets robotPose at current time. -
resetRobotPose
Clears all previous robot poses and sets robotPose at current time. -
getDebugField
-
update
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
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
-