Skip to content

Commit

Permalink
tuned some vision constants
Browse files Browse the repository at this point in the history
  • Loading branch information
catr1xLiu committed Dec 4, 2024
1 parent 2dc353c commit 1aed146
Showing 1 changed file with 5 additions and 5 deletions.
10 changes: 5 additions & 5 deletions src/main/java/frc/robot/constants/VisionConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ public class VisionConstants {

/* standard deviation for odometry and gyros */
ODOMETRY_TRANSLATIONAL_STANDARD_ERROR_METERS = 0.04,
GYRO_ROTATIONAL_STANDARD_ERROR_RADIANS = Math.toRadians(0.3);
GYRO_ROTATIONAL_STANDARD_ERROR_RADIANS = Math.toRadians(0.1);

public static final List<PhotonCameraProperties> photonVisionCameras = List.of(
new PhotonCameraProperties(
Expand Down Expand Up @@ -51,7 +51,7 @@ public class VisionConstants {
new Translation2d(0.229, 0.348),
0.2,
Rotation2d.fromDegrees(30),
30,
35,
180 // upside-down
),
new PhotonCameraProperties(
Expand All @@ -67,7 +67,7 @@ public class VisionConstants {
new Translation2d(0.229, -0.348),
0.2,
Rotation2d.fromDegrees(-30),
30,
35,
180 // upside-down
),
new PhotonCameraProperties(
Expand All @@ -83,7 +83,7 @@ public class VisionConstants {
new Translation2d(-0.229, 0.330),
0.2,
Rotation2d.fromDegrees(150),
35,
40,
180 // upside-down
),
new PhotonCameraProperties(
Expand All @@ -99,7 +99,7 @@ public class VisionConstants {
new Translation2d(-0.229, -0.330),
0.2,
Rotation2d.fromDegrees(-150),
35,
40,
180 // upside-down
));
}

0 comments on commit 1aed146

Please sign in to comment.