]> git.taranathan.com Git - FRC2026.git/commitdiff
I found every logger and made it enable only
authorWesley28w <wesleycwong@gmail.com>
Fri, 3 Apr 2026 14:28:44 +0000 (07:28 -0700)
committerWesley28w <wesleycwong@gmail.com>
Fri, 3 Apr 2026 14:28:44 +0000 (07:28 -0700)
src/main/java/frc/robot/RobotContainer.java
src/main/java/frc/robot/commands/LogCommand.java
src/main/java/frc/robot/commands/drive_comm/DefaultDriveCommand.java
src/main/java/frc/robot/commands/gpm/AutoShootCommand.java
src/main/java/frc/robot/commands/gpm/Superstructure.java
src/main/java/frc/robot/commands/vision/LogVision.java
src/main/java/frc/robot/subsystems/drivetrain/Drivetrain.java
src/main/java/frc/robot/util/Vision/Vision.java

index f18a165990d6f702bbdccf5fc6f11955dde4944c..a1d15bcc0a09d3ab5896caf88f568c28cabb4a48 100644 (file)
@@ -209,8 +209,10 @@ public class RobotContainer {
         },
         () -> drive.getChassisSpeeds(),
         (chassisSpeeds) -> {
-          Logger.recordOutput("Auto/ChassisSpeeds", chassisSpeeds);
-          drive.setChassisSpeeds(chassisSpeeds, false); // problem??
+          if (!Constants.DISABLE_LOGGING) {
+            Logger.recordOutput("Auto/ChassisSpeeds", chassisSpeeds);
+            drive.setChassisSpeeds(chassisSpeeds, false); // problem??
+          }
         },
         AutoConstants.AUTO_CONTROLLER,
         AutoConstants.CONFIG,
@@ -258,7 +260,6 @@ public class RobotContainer {
       }));
       NamedCommands.registerCommand("Stop Hood Down", new InstantCommand(() -> {
         hood.forceHoodDown(false);
-        Logger.recordOutput("hello", true);
       }));
     }
 
index e92bb5a871639840b4e39d6ab72ba693d35d0e5f..06b346db6d3354521f014136eb6085c5b263bb7c 100644 (file)
@@ -3,6 +3,7 @@ package frc.robot.commands;
 import org.littletonrobotics.junction.Logger;
 
 import edu.wpi.first.wpilibj2.command.Command;
+import frc.robot.constants.Constants;
 import frc.robot.util.Elastic;
 import frc.robot.util.HubActive;
 import frc.robot.util.Elastic.Notification;
@@ -18,8 +19,10 @@ public class LogCommand extends Command {
     @Override
     public void execute() {
         boolean current = HubActive.isHubActive();
-        Logger.recordOutput("HubActive", current);
-
+        if (!Constants.DISABLE_LOGGING) {
+            Logger.recordOutput("HubActive", current);
+        }
+        
         if (current && !hubActive) {
             Elastic.sendNotification(new Notification(NotificationLevel.INFO, "HUB ACTIVE", ""));
         } else if (!current && hubActive) {
index 727a983c16ab80a6506bf314b8107c9e0ed1ef75..a99c5c672894535faa772996fec494816ee973b8 100644 (file)
@@ -10,6 +10,7 @@ import edu.wpi.first.wpilibj.DriverStation.Alliance;
 import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
 import edu.wpi.first.wpilibj2.command.Command;
 import frc.robot.Robot;
+import frc.robot.constants.Constants;
 import frc.robot.constants.swerve.DriveConstants;
 import frc.robot.controls.BaseDriverConfig;
 import frc.robot.subsystems.drivetrain.Drivetrain;
@@ -63,8 +64,10 @@ public class DefaultDriveCommand extends Command {
         ChassisSpeeds driverInput = new ChassisSpeeds(forwardTranslation, sideTranslation, rotation);
         ChassisSpeeds corrected = DriverAssist.calculate(swerve, driverInput, swerve.getDesiredPose(), true);
 
-        Logger.recordOutput("TrenchAlign", swerve.getTrenchAlign());
-        Logger.recordOutput("AlignZones", TrenchAssistConstants.ALIGN_ZONES);
+        if (!Constants.DISABLE_LOGGING) {
+            Logger.recordOutput("TrenchAlign", swerve.getTrenchAlign());
+            Logger.recordOutput("AlignZones", TrenchAssistConstants.ALIGN_ZONES);
+        }
         if (swerve.getTrenchAlign()) {
             boolean inZone = false;
             for (Rectangle2d rectangle : TrenchAssistConstants.ALIGN_ZONES) {
@@ -90,8 +93,10 @@ public class DefaultDriveCommand extends Command {
         } else {
             swerve.setIsAlign(false);
         }
-
-        Logger.recordOutput("TrenchAssist", swerve.getTrenchAssist());
+        if (!Constants.DISABLE_LOGGING) {
+            Logger.recordOutput("TrenchAssist", swerve.getTrenchAssist());
+        }
+        
         if (swerve.getTrenchAssist()) {
             drive(TrenchAssist.calculate(swerve, corrected, trenchAssistPid));
         } else {
index 908c805eae81f114d3229a1694cc80178cc4ad71..75a9ec12848b24d542096100c8466c95d6d28bdc 100644 (file)
@@ -134,8 +134,9 @@ public class AutoShootCommand extends Command {
         turretAngleFilter.calculate(turretAngle.minus(lastTurretAngle).getRadians() / Constants.LOOP_TIME);
         
         lastTurretAngle = turretAngle;
-
-        Logger.recordOutput("Lookahead Pose", lookaheadPose);
+        if (!Constants.DISABLE_LOGGING) {
+            Logger.recordOutput("Lookahead Pose", lookaheadPose);
+        }
 
         // Subtract the rotational angle of the robot from the setpoint
         double adjustedTurretSetpoint = MathUtil.angleModulus(turretAngle.getRadians() - drivepose.getRotation().getRadians());
@@ -189,9 +190,11 @@ public class AutoShootCommand extends Command {
         hood.setFieldRelativeTarget(new Rotation2d(Units.degreesToRadians(hoodSetpoint)), hoodVelocity);
         shooter.setShooter(ShotInterpolation.exitVelocityMap.get(goalState.exitVel()));
 
-        Logger.recordOutput("Turret Calculated Setpoint", turretSetpoint);
-        Logger.recordOutput("Hood Calculate Setpoint", hoodSetpoint);
-        Logger.recordOutput("Shooter Calculate Velocity", goalState.exitVel());
+        if (!Constants.DISABLE_LOGGING) {
+            Logger.recordOutput("Turret Calculated Setpoint", turretSetpoint);
+            Logger.recordOutput("Hood Calculate Setpoint", hoodSetpoint);
+            Logger.recordOutput("Shooter Calculate Velocity", goalState.exitVel());
+        }
 
         /** Spindexer Stuff!! */
         if(spindexer != null){
index 9da140f60bcf9297ef8bf70ae835e6f61fa91d62..e937cd795cfb0d1ed2dd5217f1d1593eefe46284 100644 (file)
@@ -147,14 +147,15 @@ public class Superstructure extends Command {
         turretAngleFilter.calculate(turretAngle.minus(lastTurretAngle).getRadians() / Constants.LOOP_TIME);
         
         lastTurretAngle = turretAngle;
-
-        Logger.recordOutput("Turret/Target Pose", target);
+        
+        if (!Constants.DISABLE_LOGGING) {
+            Logger.recordOutput("Turret/Target Pose", target);
+            Logger.recordOutput("Lookahead Pose", lookaheadPose);
+        }
         SmartDashboard.putNumber("Time of flight", timeOfFlight);
         SmartDashboard.putNumber("Turret X-Velocity", turretVelocityX);
         SmartDashboard.putNumber("Turret Y-Velocity", turretVelocityY);
 
-        Logger.recordOutput("Lookahead Pose", lookaheadPose);
-
         // Subtract the rotational angle of the robot from the setpoint
         double adjustedTurretSetpoint = MathUtil.angleModulus(turretAngle.getRadians() - drivepose.getRotation().getRadians());
 
@@ -273,17 +274,22 @@ public class Superstructure extends Command {
                 shooter.setShooter(-ShotInterpolation.shooterVelocityMap.get(distanceFromTarget));
             }
 
+            if (!Constants.DISABLE_LOGGING) {
             // record when shuttling
             Logger.recordOutput("Shuttling", shuttling);
             // record distance for tuning if needed
             Logger.recordOutput("Distance From Target", distanceFromTarget);
+            }
         }
 
-        Logger.recordOutput("Turret Calculated Setpoint", turretSetpoint);
-        Logger.recordOutput("Hood Calculate Setpoint", hoodSetpoint);
-        Logger.recordOutput("Shooter Calculate Velocity", goalState.exitVel());
+        if (!Constants.DISABLE_LOGGING) {
+            Logger.recordOutput("Turret Calculated Setpoint", turretSetpoint);
+            Logger.recordOutput("Hood Calculate Setpoint", hoodSetpoint);
+            Logger.recordOutput("Shooter Calculate Velocity", goalState.exitVel());
+            
+            Logger.recordOutput("DistanceToTarget", target.getDistance(drivepose.getTranslation()));
+        }
         
-        Logger.recordOutput("DistanceToTarget", target.getDistance(drivepose.getTranslation()));
 
         SmartDashboard.putString("Phase Manager State", phaseManager.getCurrentState().toString());
 
index da5e65fbd2c5137481bf7aa44a4640756bad0a67..2f9b8b22e190f647d74f6a1eb5ffc820bcbbbaf0 100644 (file)
@@ -5,6 +5,7 @@ import java.util.function.Supplier;
 import org.littletonrobotics.junction.Logger;
 
 import edu.wpi.first.wpilibj2.command.Command;
+import frc.robot.constants.Constants;
 import frc.robot.util.Vision.DetectedObject;
 
 public class LogVision extends Command {
@@ -17,8 +18,10 @@ public class LogVision extends Command {
     public void execute() {
         DetectedObject object = this.objectSupplier.get();
         if (object != null) {
-            Logger.recordOutput("Vision/object_angle", object.getAngle());
-            Logger.recordOutput("Vision/object_distance", object.getDistance());
+            if (!Constants.DISABLE_LOGGING) {
+                Logger.recordOutput("Vision/object_angle", object.getAngle());
+                Logger.recordOutput("Vision/object_distance", object.getDistance());
+            }
         }
     }
 
index dc50b4707a98bc7c2d6b0decc2064351662a3742..4415c8a8928f5abdc250cac6595b99081fc42257 100644 (file)
@@ -173,12 +173,16 @@ public class Drivetrain extends SubsystemBase {
 
         PathPlannerLogging.setLogActivePathCallback(
                 (activePath) -> {
-                    Logger.recordOutput(
-                            "Odometry/Trajectory", activePath.toArray(new Pose2d[activePath.size()]));
+                    if (!Constants.DISABLE_LOGGING) {
+                        Logger.recordOutput(
+                                "Odometry/Trajectory", activePath.toArray(new Pose2d[activePath.size()]));
+                    }
                 });
         PathPlannerLogging.setLogTargetPoseCallback(
                 (targetPose) -> {
-                    Logger.recordOutput("Odometry/TrajectorySetpoint", targetPose);
+                    if (!Constants.DISABLE_LOGGING) {
+                        Logger.recordOutput("Odometry/TrajectorySetpoint", targetPose);
+                    }
                 });
 
         // PPLibTelemetry.enableCompetitionMode();
@@ -338,9 +342,10 @@ public class Drivetrain extends SubsystemBase {
                             double gyroYawAtTimestamp = getGyroYawAtTimestamp(visionPose.timestampSeconds);
 
                             if (!Double.isNaN(gyroYawAtTimestamp)) {
-
-                                Logger.recordOutput("GyroYaw", Math.toDegrees(gyroYawAtTimestamp));
-                                Logger.recordOutput("VisionYaw", Math.toDegrees(visionYaw));
+                                if (!Constants.DISABLE_LOGGING) {
+                                    Logger.recordOutput("GyroYaw", Math.toDegrees(gyroYawAtTimestamp));
+                                    Logger.recordOutput("VisionYaw", Math.toDegrees(visionYaw));
+                                }
                                 // use weighted observation
                                 gyroBiasEstimator.addObservation(visionYaw, gyroYawAtTimestamp, 1.0);
                             }
index 4b184cb089345697c8075b639a7ba42d13b9f8d5..01825bc2d3c67a064127f5a71cf9b7c9c6fe9dac 100644 (file)
@@ -101,7 +101,9 @@ public class Vision {
     for (int i = 0; i < FieldConstants.field.getTags().size(); i++) {
       tags[i] = (FieldConstants.field.getTagPose(i+1).get());
     }
-    Logger.recordOutput("AprilTags", tags);
+    if (!Constants.DISABLE_LOGGING) {
+      Logger.recordOutput("AprilTags", tags);
+    }
   }