mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-20 00:51:41 +00:00
Bump wpilib versions to 2024 beta 1 (#947)
This commit is contained in:
@@ -36,7 +36,6 @@ import edu.wpi.first.math.geometry.Translation3d;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import edu.wpi.first.math.numbers.N3;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import java.io.IOException;
|
||||
|
||||
public class Constants {
|
||||
public static class Vision {
|
||||
@@ -46,16 +45,8 @@ public class Constants {
|
||||
new Transform3d(new Translation3d(0.5, 0.0, 0.5), new Rotation3d(0, 0, 0));
|
||||
|
||||
// The layout of the AprilTags on the field
|
||||
public static final AprilTagFieldLayout kTagLayout;
|
||||
|
||||
static {
|
||||
try {
|
||||
kTagLayout = AprilTagFields.kDefaultField.loadAprilTagLayoutField();
|
||||
} catch (IOException e) {
|
||||
e.printStackTrace();
|
||||
throw new RuntimeException(e);
|
||||
}
|
||||
}
|
||||
public static final AprilTagFieldLayout kTagLayout =
|
||||
AprilTagFields.kDefaultField.loadAprilTagLayoutField();
|
||||
|
||||
// The standard deviations of our vision estimated poses, which affect correction rate
|
||||
// (Fake values. Experiment and determine estimation noise on an actual robot.)
|
||||
|
||||
Reference in New Issue
Block a user