photonlibpy.simulation.visionSystemSim
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. :class:.VisionTargetSim
s added to
this class will be detected by the :class:.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.
__init__(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. :class:.VisionTargetSim
s added to
this class will be detected by the :class:.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.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
visionSystemName
|
str
|
The specific identifier for this vision system in NetworkTables. |
required |
addAprilTags(layout)
Adds targets on the field which your vision system is designed to detect. The {@link PhotonCamera}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:
Name | Type | Description | Default |
---|---|---|---|
tagLayout
|
The field tag layout to get Apriltag poses and IDs from |
required |
addCamera(cameraSim, 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 :class:.PhotonCamera
.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
cameraSim
|
PhotonCameraSim
|
The camera simulation |
required |
robotToCamera
|
Transform3d
|
The transform from the robot pose to the camera pose |
required |
addVisionTargets(targets, targetType='targets')
Adds targets on the field which your vision system is designed to detect. The {@link PhotonCamera}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:
Name | Type | Description | Default |
---|---|---|---|
targets
|
list[VisionTargetSim]
|
Targets to add to the simulated field |
required |
type
|
Type of target (e.g. "cargo"). |
required |
adjustCamera(cameraSim, 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:
Name | Type | Description | Default |
---|---|---|---|
cameraSim
|
PhotonCameraSim
|
The simulated camera to change the relative position of |
required |
robotToCamera
|
Transform3d
|
New transform from the robot to the camera |
required |
Returns:
Type | Description |
---|---|
bool
|
If the cameraSim was valid and transform was adjusted |
clearCameras()
Remove all simulated cameras from this vision system.
getCameraPose(cameraSim, time=wpilib.Timer.getFPGATimestamp())
Get a simulated camera's position on the field. If the requested camera is invalid, an empty optional is returned.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
cameraSim
|
PhotonCameraSim
|
The specific camera to get the field pose of |
required |
Returns:
Type | Description |
---|---|
Pose3d | None
|
The pose of this camera, or an empty optional if it is invalid |
getCameraSim(name)
Get one of the simulated cameras.
getCameraSims()
Get all the simulated cameras.
getRobotPose(timestamp=wpilib.Timer.getFPGATimestamp())
Get the robot pose in meters saved by the vision system at this timestamp.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
timestamp
|
seconds
|
Timestamp of the desired robot pose |
getFPGATimestamp()
|
getRobotToCamera(cameraSim, time=wpilib.Timer.getFPGATimestamp())
Get a simulated camera's position relative to the robot. If the requested camera is invalid, an empty optional is returned.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
cameraSim
|
PhotonCameraSim
|
The specific camera to get the robot-to-camera transform of |
required |
timeSeconds
|
Timestamp in seconds of when the transform should be observed |
required |
Returns:
Type | Description |
---|---|
Transform3d | None
|
The transform of this camera, or an empty optional if it is invalid |
removeCamera(cameraSim)
Remove a simulated camera from this vision system.
Returns:
Type | Description |
---|---|
bool
|
If the camera was present and removed |
resetCameraTransforms(cameraSim=None)
Reset the transform history for this camera to just the current transform.
resetRobotPose(robotPose)
Clears all previous robot poses and sets robotPose at current time.
update(robotPose)
Periodic update. Ensure this is called repeatedly-- camera performance is used to automatically determine if a new frame should be submitted.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
robotPoseMeters
|
The simulated robot pose in meters |
required |