mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-19 00:41:41 +00:00
[NFC] Update RobotPoseEstimator documentation (#740)
* update documentation * add suggested changes * rename April Tag to AprilTag * Update RobotPoseEstimator.java Co-authored-by: Mohammad Durrani <46766905+mdurrani808@users.noreply.github.com>
This commit is contained in:
@@ -41,7 +41,7 @@ import org.photonvision.targeting.PhotonPipelineResult;
|
||||
import org.photonvision.targeting.PhotonTrackedTarget;
|
||||
|
||||
/**
|
||||
* The PhotonPoseEstimator class filters or combines readings from all the fiducials visible at a
|
||||
* The PhotonPoseEstimator class filters or combines readings from all the AprilTags 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.
|
||||
*/
|
||||
@@ -76,12 +76,16 @@ public class PhotonPoseEstimator {
|
||||
/**
|
||||
* Create a new PhotonPoseEstimator.
|
||||
*
|
||||
* @param fieldTags A WPILib {@link AprilTagFieldLayout} linking AprilTag IDs to Pose3ds with
|
||||
* respect to the FIRST field.
|
||||
* @param fieldTags A WPILib {@link AprilTagFieldLayout} linking AprilTag IDs to Pose3d objects
|
||||
* with respect to the FIRST field using the <a
|
||||
* href="https://docs.wpilib.org/en/stable/docs/software/advanced-controls/geometry/coordinate-systems.html#field-coordinate-system">Field
|
||||
* Coordinate System</a>.
|
||||
* @param strategy The strategy it should use to determine the best pose.
|
||||
* @param camera PhotonCameras and
|
||||
* @param robotToCamera Transform3d from the center of the robot to the camera mount positions
|
||||
* (ie, robot ➔ camera).
|
||||
* (ie, robot ➔ camera) in the <a
|
||||
* href="https://docs.wpilib.org/en/stable/docs/software/advanced-controls/geometry/coordinate-systems.html#robot-coordinate-system">Robot
|
||||
* Coordinate System</a>.
|
||||
*/
|
||||
public PhotonPoseEstimator(
|
||||
AprilTagFieldLayout fieldTags,
|
||||
@@ -176,7 +180,7 @@ public class PhotonPoseEstimator {
|
||||
* @param lastPose the lastPose to set
|
||||
*/
|
||||
public void setLastPose(Pose2d lastPose) {
|
||||
this.lastPose = new Pose3d(lastPose);
|
||||
setLastPose(new Pose3d(lastPose));
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -485,7 +489,7 @@ public class PhotonPoseEstimator {
|
||||
private void reportFiducialPoseError(int fiducialId) {
|
||||
if (!reportedErrors.contains(fiducialId)) {
|
||||
DriverStation.reportError(
|
||||
"[PhotonPoseEstimator] Tried to get pose of unknown April Tag: " + fiducialId, false);
|
||||
"[PhotonPoseEstimator] Tried to get pose of unknown AprilTag: " + fiducialId, false);
|
||||
reportedErrors.add(fiducialId);
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user