mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-19 00:41:41 +00:00
Fix calibration NT table in PhotonCamera (#805)
* Fix wrong table in calibration subscriber * Update example to load 2023 layout * Update PhotonCamera.java
This commit is contained in:
@@ -24,14 +24,11 @@
|
||||
|
||||
package frc.robot;
|
||||
|
||||
import edu.wpi.first.apriltag.AprilTag;
|
||||
import edu.wpi.first.apriltag.AprilTagFieldLayout;
|
||||
import edu.wpi.first.apriltag.AprilTagFields;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Pose3d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import frc.robot.Constants.FieldConstants;
|
||||
import frc.robot.Constants.VisionConstants;
|
||||
import java.util.ArrayList;
|
||||
import java.io.IOException;
|
||||
import java.util.Optional;
|
||||
import org.photonvision.EstimatedRobotPose;
|
||||
import org.photonvision.PhotonCamera;
|
||||
@@ -43,38 +40,21 @@ public class PhotonCameraWrapper {
|
||||
public PhotonPoseEstimator photonPoseEstimator;
|
||||
|
||||
public PhotonCameraWrapper() {
|
||||
// Set up a test arena of two apriltags at the center of each driver station set
|
||||
final AprilTag tag18 =
|
||||
new AprilTag(
|
||||
18,
|
||||
new Pose3d(
|
||||
new Pose2d(
|
||||
FieldConstants.length,
|
||||
FieldConstants.width / 2.0,
|
||||
Rotation2d.fromDegrees(180))));
|
||||
final AprilTag tag01 =
|
||||
new AprilTag(
|
||||
01,
|
||||
new Pose3d(new Pose2d(0.0, FieldConstants.width / 2.0, Rotation2d.fromDegrees(0.0))));
|
||||
ArrayList<AprilTag> atList = new ArrayList<AprilTag>();
|
||||
atList.add(tag18);
|
||||
atList.add(tag01);
|
||||
AprilTagFieldLayout atfl = null;
|
||||
try {
|
||||
atfl = AprilTagFields.k2023ChargedUp.loadAprilTagLayoutField();
|
||||
} catch (IOException e) {
|
||||
e.printStackTrace();
|
||||
}
|
||||
|
||||
// TODO - once 2023 happens, replace this with just loading the 2023 field arrangement
|
||||
AprilTagFieldLayout atfl =
|
||||
new AprilTagFieldLayout(atList, FieldConstants.length, FieldConstants.width);
|
||||
|
||||
// Forward Camera
|
||||
photonCamera =
|
||||
new PhotonCamera(
|
||||
VisionConstants
|
||||
.cameraName); // Change the name of your camera here to whatever it is in the
|
||||
// PhotonVision UI.
|
||||
// Change the name of your camera here to whatever it is in the PhotonVision UI.
|
||||
photonCamera = new PhotonCamera(VisionConstants.cameraName);
|
||||
|
||||
// Create pose estimator
|
||||
photonPoseEstimator =
|
||||
new PhotonPoseEstimator(
|
||||
atfl, PoseStrategy.CLOSEST_TO_REFERENCE_POSE, photonCamera, VisionConstants.robotToCam);
|
||||
atfl, PoseStrategy.MULTI_TAG_PNP, photonCamera, VisionConstants.robotToCam);
|
||||
photonPoseEstimator.setMultiTagFallbackStrategy(PoseStrategy.LOWEST_AMBIGUITY);
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
Reference in New Issue
Block a user