PhotonPoseEstimator
- class photonvision.PhotonPoseEstimator(aprilTags: robotpy_apriltag._apriltag.AprilTagFieldLayout, strategy: photonvision._photonvision.PoseStrategy, camera: photonvision._photonvision.PhotonCamera, robotToCamera: wpimath.geometry._geometry.Transform3d)
Bases:
pybind11_object
The PhotonPoseEstimator class filters or combines readings from all the fiducials visible at a given timestamp on the field to produce a single robot in field pose, using the strategy set below. Example usage can be found in our apriltagExample example project.
Create a new PhotonPoseEstimator.
- Parameters:
aprilTags – A AprilTagFieldLayout linking AprilTag IDs to Pose3ds with respect to the FIRST field.
strategy – The strategy it should use to determine the best pose.
camera – The PhotonCamera.
robotToCamera – Transform3d from the center of the robot to the camera mount positions (ie, robot ➔ camera).
- getCamera() photonvision._photonvision.PhotonCamera
- getFieldLayout() robotpy_apriltag._apriltag.AprilTagFieldLayout
Get the AprilTagFieldLayout being used by the PositionEstimator.
- Returns:
the AprilTagFieldLayout
- getPoseStrategy() photonvision._photonvision.PoseStrategy
Get the Position Estimation Strategy being used by the Position Estimator.
- Returns:
the strategy
- getReferencePose() wpimath.geometry._geometry.Pose3d
Return the reference position that is being used by the estimator.
- Returns:
the referencePose
- getRobotToCameraTransform() wpimath.geometry._geometry.Transform3d
- Returns:
The current transform from the center of the robot to the camera mount position.
- setLastPose(lastPose: wpimath.geometry._geometry.Pose3d) None
Update the stored last pose. Useful for setting the initial estimate when using the CLOSEST_TO_LAST_POSE strategy.
- Parameters:
lastPose – the lastPose to set
- setMultiTagFallbackStrategy(strategy: photonvision._photonvision.PoseStrategy) None
Set the Position Estimation Strategy used in multi-tag mode when only one tag can be seen. Must NOT be MULTI_TAG_PNP
- Parameters:
strategy – the strategy to set
- setPoseStrategy(strat: photonvision._photonvision.PoseStrategy) None
Set the Position Estimation Strategy used by the Position Estimator.
- Parameters:
strategy – the strategy to set
- setReferencePose(referencePose: wpimath.geometry._geometry.Pose3d) None
Update the stored reference pose for use when using the CLOSEST_TO_REFERENCE_POSE strategy.
- Parameters:
referencePose – the referencePose to set
- setRobotToCameraTransform(robotToCamera: wpimath.geometry._geometry.Transform3d) None
Useful for pan and tilt mechanisms, or cameras on turrets
- Parameters:
robotToCamera – The current transform from the center of the robot to the camera mount position.
- update(*args, **kwargs)
Overloaded function.
update(self: photonvision._photonvision.PhotonPoseEstimator) -> Optional[photonvision._photonvision.EstimatedRobotPose]
Update the pose estimator. Internally grabs a new PhotonPipelineResult from the camera and process it.
update(self: photonvision._photonvision.PhotonPoseEstimator, result: photonvision._photonvision.PhotonPipelineResult) -> Optional[photonvision._photonvision.EstimatedRobotPose]
Update the pose estimator.