From 50ff1b10c97bae69b45052f5b5558cd9445d7663 Mon Sep 17 00:00:00 2001 From: Nilesh Agarwalla Date: Thu, 4 Apr 2024 21:27:39 -0400 Subject: [PATCH] Added left/right vision cameras --- .../robot/commands/auto/AutoNamedCommands.java | 4 +++- .../java/frc/robot/config/RobotConfigInferno.java | 15 +++++++++------ 2 files changed, 12 insertions(+), 7 deletions(-) diff --git a/src/main/java/frc/robot/commands/auto/AutoNamedCommands.java b/src/main/java/frc/robot/commands/auto/AutoNamedCommands.java index f9e248d8..e9918faa 100644 --- a/src/main/java/frc/robot/commands/auto/AutoNamedCommands.java +++ b/src/main/java/frc/robot/commands/auto/AutoNamedCommands.java @@ -51,7 +51,9 @@ public static class AutoConstants { 28, ArmConstants.noteScoreAngleInDegrees, ShooterConstants.velocityInRPM); public static AutoScoreConstants scoreFromBetween2and3 = new AutoScoreConstants( - 11, ArmConstants.subwooferScoreFromPodiumAngleInDegrees, ShooterConstants.velocityInRPM); + 11, + ArmConstants.subwooferScoreFromPodiumAngleInDegrees, + ShooterConstants.velocityInRPM); } public static void configure() { diff --git a/src/main/java/frc/robot/config/RobotConfigInferno.java b/src/main/java/frc/robot/config/RobotConfigInferno.java index bcc27ae8..8862d2e9 100644 --- a/src/main/java/frc/robot/config/RobotConfigInferno.java +++ b/src/main/java/frc/robot/config/RobotConfigInferno.java @@ -148,15 +148,16 @@ public RobotConfigInferno() { new Translation3d(0.3048, 0, 0.22), new Rotation3d(0, Units.degreesToRadians(-30), Units.degreesToRadians(0))))); - /* cameras.add( new VisionCamera( "right", "1196", new Transform3d( new Translation3d( - -Units.inchesToMeters(5.25), -Units.inchesToMeters(11.25), Units.inchesToMeters(7)), - new Rotation3d(0, Units.degreesToRadians(-30), Units.degreesToRadians(-90))))); + -Units.inchesToMeters(5.25), + -Units.inchesToMeters(11.25), + Units.inchesToMeters(7)), + new Rotation3d(0, Units.degreesToRadians(-32), Units.degreesToRadians(-90))))); cameras.add( new VisionCamera( @@ -164,9 +165,11 @@ public RobotConfigInferno() { "1190", new Transform3d( new Translation3d( - -Units.inchesToMeters(5.25), Units.inchesToMeters(11.25), Units.inchesToMeters(7)), - new Rotation3d(0, Units.degreesToRadians(-30), Units.degreesToRadians(90))))); - */ + -Units.inchesToMeters(5.25), + Units.inchesToMeters(11.25), + Units.inchesToMeters(7)), + new Rotation3d(0, Units.degreesToRadians(-32), Units.degreesToRadians(90))))); + VisionConstants.visionDistanceOffsetInMeters = -0.2; vision = new VisionSubsystem(cameras, AprilTagFields.k2024Crescendo.loadAprilTagLayoutField());