From 0a80d7765560e951c58a586f0dc321475846bf5c Mon Sep 17 00:00:00 2001 From: maxwtan <100314265+MaxwellTTan20@users.noreply.github.com> Date: Tue, 24 Feb 2026 16:55:15 -0800 Subject: [PATCH] camera positions --- .../frc/robot/constants/VisionConstants.java | 36 ++++++++++--------- 1 file changed, 20 insertions(+), 16 deletions(-) diff --git a/src/main/java/frc/robot/constants/VisionConstants.java b/src/main/java/frc/robot/constants/VisionConstants.java index 39cf88a..ef784cc 100644 --- a/src/main/java/frc/robot/constants/VisionConstants.java +++ b/src/main/java/frc/robot/constants/VisionConstants.java @@ -155,31 +155,35 @@ public class VisionConstants { new Pair( "CameraFrontLeft", new Transform3d( - new Translation3d(Units.inchesToMeters(10.485), Units.inchesToMeters(10.217), - Units.inchesToMeters(11.012)), - new Rotation3d(0, Units.degreesToRadians(-11), - Math.PI/2 + Units.degreesToRadians(20)))), + new Translation3d(Units.inchesToMeters(10.965663), + Units.inchesToMeters(-8.602606), + Units.inchesToMeters(19.337757)), + new Rotation3d(0, Units.degreesToRadians(-22.0), + Units.degreesToRadians(55.0)))), new Pair( "CameraFrontRight", new Transform3d( - new Translation3d(Units.inchesToMeters(-9.538), Units.inchesToMeters(7.474), - Units.inchesToMeters(8.719)), - new Rotation3d(0, Units.degreesToRadians(-19.5), - Math.PI/2-Units.degreesToRadians(25)))), + new Translation3d(Units.inchesToMeters(-10.965663), + Units.inchesToMeters(-8.602606), + Units.inchesToMeters(19.337757)), + new Rotation3d(0, Units.degreesToRadians(-22.0), + Units.degreesToRadians(-55.0)))), new Pair( "CameraBackLeft", new Transform3d( - new Translation3d(Units.inchesToMeters(-9.538), Units.inchesToMeters(7.474), - Units.inchesToMeters(8.719)), - new Rotation3d(0, Units.degreesToRadians(-19.5), - Math.PI/2-Units.degreesToRadians(25)))), + new Translation3d(Units.inchesToMeters(10.518135), + Units.inchesToMeters(-11.140663), + Units.inchesToMeters(19.337757)), + new Rotation3d(0, Units.degreesToRadians(-22.0), + Units.degreesToRadians(145.0)))), new Pair( "CameraBackRight", new Transform3d( - new Translation3d(Units.inchesToMeters(-9.538), Units.inchesToMeters(7.474), - Units.inchesToMeters(8.719)), - new Rotation3d(0, Units.degreesToRadians(-19.5), - Math.PI/2-Units.degreesToRadians(25)))) + new Translation3d(Units.inchesToMeters(-10.518135), + Units.inchesToMeters(-11.140663), + Units.inchesToMeters(19.337757)), + new Rotation3d(0, Units.degreesToRadians(-22.0), + Units.degreesToRadians(-145.0)))) )); /** -- 2.39.5