]> git.taranathan.com Git - FRC2026.git/commitdiff
bruh robot broke
authorWesleyWong-972 <wesleycwong@gmail.com>
Wed, 25 Mar 2026 22:21:33 +0000 (15:21 -0700)
committerWesleyWong-972 <wesleycwong@gmail.com>
Wed, 25 Mar 2026 22:21:33 +0000 (15:21 -0700)
src/main/java/frc/robot/commands/gpm/Superstructure.java
src/main/java/frc/robot/constants/FieldConstants.java
src/main/java/frc/robot/subsystems/hood/Hood.java

index d1bdf15445bed24986be3e33f42bceb76848450b..fe58991f626e4ce294e536127005342aa2e03af7 100644 (file)
@@ -235,7 +235,7 @@ public class Superstructure extends Command {
                 System.out.println("Hood forced down");
             } else {
                 hood.forceHoodDown(false);
-                System.out.println("Hood forced down");
+                System.out.println("Hood forced up");
             }
             shooter.setShooter(-ShotInterpolation.shooterVelocityMap.get(distanceFromTarget));
             Logger.recordOutput("Distance From Target", distanceFromTarget);
index 644550850a907dced58e1a3d5c6889b53dd70a69..d114d054c5dac3708bdebf284fc24cf921e972ab 100644 (file)
@@ -193,7 +193,8 @@ public class FieldConstants {
 
   public static boolean underTrench(double x, double y) {
     // ensures we aren't in center channel
-    if (y > Units.inchesToMeters(50.0) && y < FIELD_WIDTH - Units.inchesToMeters(50)) {
+    if (y > Units.inchesToMeters(50.0
+    ) && y < FIELD_WIDTH - Units.inchesToMeters(50)) {
       return false;
     }
     // if our location is to far away from right underneath trench in terms of x
index 2623ff2e557c6c9f68ce61f95fa88a0e1ff13d43..c92a52f848cf17ca945434574985e16806cfd7bb 100644 (file)
@@ -103,9 +103,9 @@ public class Hood extends SubsystemBase implements HoodIO {
                // SmartDashboard.putNumber("Hood Setpoint", goalAngle.getDegrees());
 
                if (forceHoodDown){
-                       System.out.println("Forcing the hood down");
                        goalAngle = Rotation2d.fromDegrees(HoodConstants.MAX_ANGLE);
                        goalVelocityRadPerSec = 0.0;
+               } else {
                }
 
                double setpointRad = goalAngle.getRadians();