]> git.taranathan.com Git - FRC2026.git/commitdiff
boolean to disable logging
authoriefomit <timofei.stem@gmail.com>
Fri, 3 Apr 2026 07:10:59 +0000 (00:10 -0700)
committeriefomit <timofei.stem@gmail.com>
Fri, 3 Apr 2026 07:10:59 +0000 (00:10 -0700)
src/main/java/frc/robot/constants/Constants.java
src/main/java/frc/robot/subsystems/Climb/LinearClimb.java
src/main/java/frc/robot/subsystems/Intake/Intake.java
src/main/java/frc/robot/subsystems/drivetrain/Drivetrain.java
src/main/java/frc/robot/subsystems/drivetrain/Module.java
src/main/java/frc/robot/subsystems/hood/Hood.java
src/main/java/frc/robot/subsystems/shooter/Shooter.java
src/main/java/frc/robot/subsystems/spindexer/Spindexer.java
src/main/java/frc/robot/subsystems/turret/Turret.java
src/main/java/frc/robot/util/Vision/Vision.java

index 2cf72f11ef5d2609fbbd22e7d98459668288a433..cfa252c09611af1749669873cbdf50640b88b5af 100644 (file)
@@ -20,6 +20,9 @@ public class Constants {
     // Logging 
     public static final boolean USE_TELEMETRY = true;
 
+    // this would disable all logger calls
+    public static final boolean DISABLE_LOGGING = true;
+
     public static enum Mode {
         /** Running on a real robot. */
         REAL,
index 14d97d3c535643b55bcfd90c010b0eb8a76caca5..f5059174dcc970637fb393a22e8bf80f3bb61d40 100644 (file)
@@ -156,10 +156,14 @@ public class LinearClimb extends SubsystemBase implements LinearClimbIO {
         SmartDashboard.putBoolean("Climb Calibrated", !calibrating);
         SmartDashboard.putBoolean("Climb At Setpoint", atSetPoint());
 
-        Logger.recordOutput("LinearClimb setpointMeters", Units.rotationsToRadians(pid.getSetpoint())
-                * ClimbConstants.WHEEL_RADIUS / ClimbConstants.CLIMB_GEAR_RATIO);
+        if (!Constants.DISABLE_LOGGING) {
+            Logger.recordOutput("LinearClimb setpointMeters", Units.rotationsToRadians(pid.getSetpoint())
+                    * ClimbConstants.WHEEL_RADIUS / ClimbConstants.CLIMB_GEAR_RATIO);
+        }
         updateInputs();
-        Logger.processInputs("LinearClimb", inputs);
+        if (!Constants.DISABLE_LOGGING) {
+            Logger.processInputs("LinearClimb", inputs);
+        }
     }
 
     /**
index c1fca0af01d99549a812034f214ef43296c063b0..488fef52b5919dc321fcfec2cbb2c1cde99203ea 100644 (file)
@@ -188,10 +188,12 @@ public class Intake extends SubsystemBase implements IntakeIO{
     }
 
     public void periodic() {
-        // Report position to SmartDashboard
         double inchExtension = getPosition();
-        Logger.recordOutput("Intake/Setpoint", setpointInches);
-        robotExtension.setLength(inchExtension);
+        
+        if (!Constants.DISABLE_LOGGING) {
+            Logger.recordOutput("Intake/Setpoint", setpointInches);
+            robotExtension.setLength(inchExtension);
+        }
 
         SmartDashboard.putNumber("Intake Extension (in)", inchExtension);
         SmartDashboard.putBoolean("Intake Extended", inchExtension > 1.0);
@@ -206,7 +208,9 @@ public class Intake extends SubsystemBase implements IntakeIO{
         }
 
         updateInputs();
-        Logger.processInputs("Intake", inputs);
+        if (!Constants.DISABLE_LOGGING) {
+            Logger.processInputs("Intake", inputs);
+        }
 
         SmartDashboard.putBoolean("Intake Calibrated", !calibrating);
         SmartDashboard.putBoolean("Intake At Setpoint", Math.abs(inchExtension - setpointInches) < 0.5);
index 550765ef19bc057386ef56fa51413eda71a8ec7c..dc50b4707a98bc7c2d6b0decc2064351662a3742 100644 (file)
@@ -197,7 +197,9 @@ public class Drivetrain extends SubsystemBase {
     public void periodic() {
         odometryLock.lock(); // Prevents odometry updates while reading data
         gyroIO.updateInputs(gyroInputs);
-        Logger.processInputs("Drive/Gyro", gyroInputs);
+        if (!Constants.DISABLE_LOGGING) {
+            Logger.processInputs("Drive/Gyro", gyroInputs);
+        }
         for (var module : modules) {
             module.periodic();
         }
@@ -228,7 +230,9 @@ public class Drivetrain extends SubsystemBase {
             // Apply update
             poseEstimator.updateWithTime(sampleTimestamps[i], rawGyroRotation, modulePositions);
         }
-        Logger.recordOutput("Odometry/module poses", modulePoses.getModulePoses());
+        if (!Constants.DISABLE_LOGGING) {
+            Logger.recordOutput("Odometry/module poses", modulePoses.getModulePoses());
+        }
         updateOdometryVision();
 
         field.setRobotPose(getPose());
index 7c01282a193f37728bd026e5f012cdaf357216f5..4ff8670290dde707dd0a794e7be55fb9ece952ee 100644 (file)
@@ -28,6 +28,7 @@ import edu.wpi.first.math.kinematics.SwerveModulePosition;
 import edu.wpi.first.math.kinematics.SwerveModuleState;
 import edu.wpi.first.math.util.Units;
 import edu.wpi.first.units.measure.Angle;
+import frc.robot.constants.Constants;
 import edu.wpi.first.units.measure.AngularVelocity;
 import edu.wpi.first.units.measure.Current;
 import edu.wpi.first.units.measure.Voltage;
@@ -209,7 +210,9 @@ public class Module implements ModuleIO{
     
     public void periodic() {
         updateInputs();
-        Logger.processInputs("Drive/Module" + Integer.toString(moduleConstants.ordinal()), inputs);
+        if (!Constants.DISABLE_LOGGING) {
+            Logger.processInputs("Drive/Module" + Integer.toString(moduleConstants.ordinal()), inputs);
+        }
 
          // Calculate positions for odometry
         int sampleCount = inputs.odometryTimestamps.length; // All signals are sampled together
@@ -223,7 +226,9 @@ public class Module implements ModuleIO{
         driveDisconnectedAlert.set(!inputs.driveConnected);
         turnDisconnectedAlert.set(!inputs.turnConnected);
         turnEncoderDisconnectedAlert.set(!inputs.turnEncoderConnected);
-        Logger.recordOutput("Angle "+ moduleConstants.ordinal(), MathUtil.inputModulus(getAngle().getDegrees(), 0, 360));
+        if (!Constants.DISABLE_LOGGING) {
+            Logger.recordOutput("Angle "+ moduleConstants.ordinal(), MathUtil.inputModulus(getAngle().getDegrees(), 0, 360));
+        }
     }
 
     public void setDesiredState(SwerveModuleState wantedState, boolean isOpenLoop) {
@@ -250,7 +255,9 @@ public class Module implements ModuleIO{
             driveMotor.set(percentOutput);
         } else {
             double velocity = desiredState.speedMetersPerSecond/DriveConstants.WHEEL_RADIUS/2/Math.PI*DriveConstants.DRIVE_GEAR_RATIO;
-            Logger.recordOutput("desired vel" + moduleConstants.ordinal(), velocity);
+            if (!Constants.DISABLE_LOGGING) {
+                Logger.recordOutput("desired vel" + moduleConstants.ordinal(), velocity);
+            }
             
             double feedforward = velocity * moduleConstants.getDriveV();
             driveMotor.setControl(
index 5620b76d1b1d9a120e9bccb5a3d401feb9657ed7..34425fab515cdc7b00dae05fa7a80aca140ec972 100644 (file)
@@ -104,7 +104,9 @@ public class Hood extends SubsystemBase implements HoodIO {
     @Override
     public void periodic() {
                updateInputs();
-               Logger.processInputs("Hood", inputs);
+               if (!Constants.DISABLE_LOGGING) {
+                       Logger.processInputs("Hood", inputs);
+               }
 
                // goalAngle = Rotation2d.fromDegrees(SmartDashboard.getNumber("Hood Setpoint", goalAngle.getDegrees()));
                // SmartDashboard.putNumber("Hood Setpoint", goalAngle.getDegrees());
@@ -151,9 +153,11 @@ public class Hood extends SubsystemBase implements HoodIO {
                        .withFeedForward(velocityCompensation));
                }
 
-        Logger.recordOutput("Hood/Voltage", motor.getMotorVoltage().getValue());
-               Logger.recordOutput("Hood/velocitySetpoint", goalVelocityRadPerSec / HoodConstants.HOOD_GEAR_RATIO);
-               Logger.recordOutput("Hood/SetpointDeg", Units.radiansToDegrees(goalAngle.getRadians()));
+        if (!Constants.DISABLE_LOGGING) {
+            Logger.recordOutput("Hood/Voltage", motor.getMotorVoltage().getValue());
+            Logger.recordOutput("Hood/velocitySetpoint", goalVelocityRadPerSec / HoodConstants.HOOD_GEAR_RATIO);
+            Logger.recordOutput("Hood/SetpointDeg", Units.radiansToDegrees(goalAngle.getRadians()));
+        }
 
                SmartDashboard.putBoolean("Hood Calibrated", !calibrating);
                SmartDashboard.putBoolean("Hood At Setpoint", Math.abs(getPositionDeg() - goalAngle.getDegrees()) < 2.0);
index 74d11314f0e482e7bfb18e5674815a303b10cd8d..882ffc86f7867ae107adda1ff3148b7bd13456b4 100644 (file)
@@ -93,8 +93,10 @@ public class Shooter extends SubsystemBase implements ShooterIO {
         shooterMotorLeft.setControl(voltageRequest.withVelocity(targetVelocityRPS));
         shooterMotorRight.setControl(voltageRequest.withVelocity(targetVelocityRPS));   
         
-        Logger.recordOutput("Shooter/realVelocity", shooterMotorLeft.getVelocity().getValueAsDouble() * ShooterConstants.SHOOTER_LAUNCH_DIAMETER);
-        Logger.recordOutput("Shooter/targetVelocity", shooterTargetSpeed);
+        if (!Constants.DISABLE_LOGGING) {
+            Logger.recordOutput("Shooter/realVelocity", shooterMotorLeft.getVelocity().getValueAsDouble() * ShooterConstants.SHOOTER_LAUNCH_DIAMETER);
+            Logger.recordOutput("Shooter/targetVelocity", shooterTargetSpeed);
+        }
 
         double actualWheelVelocity = shooterMotorLeft.getVelocity().getValueAsDouble() * ShooterConstants.SHOOTER_LAUNCH_DIAMETER;
         
@@ -134,7 +136,9 @@ public class Shooter extends SubsystemBase implements ShooterIO {
         inputs.shooterCurrentRight = shooterMotorRight.getStatorCurrent().getValueAsDouble();
 
 
-        Logger.processInputs("Shooter", inputs);
+        if (!Constants.DISABLE_LOGGING) {
+            Logger.processInputs("Shooter", inputs);
+        }
     }
 
     /**
index a4a1014c46b4ff330ca430ff81bc4775ccdb6c3e..e61eafc18d8a89101dc4d5a0fe0153a9df6a5d23 100644 (file)
@@ -50,8 +50,10 @@ public class Spindexer extends SubsystemBase implements SpindexerIO {
 
     @Override
     public void periodic() {
-        updateInputs();
-        Logger.processInputs("Spindexer", inputs);
+        if (!Constants.DISABLE_LOGGING) {
+            updateInputs();
+            Logger.processInputs("Spindexer", inputs);
+        }
 
         if (resetPos == null) {
             motor.setPosition(0.1 * gearRatio);
@@ -133,7 +135,9 @@ public class Spindexer extends SubsystemBase implements SpindexerIO {
     public void updateInputs() {
         inputs.spindexerVelocity = motor.getVelocity().getValueAsDouble(); //SpindexerConstants.gearRatio;
         inputs.spindexerCurrent = motor.getStatorCurrent().getValueAsDouble();
-        Logger.processInputs("Spindexer", inputs);
+        if (!Constants.DISABLE_LOGGING) {
+            Logger.processInputs("Spindexer", inputs);
+        }
     }
 
     private Double resetPos;
index 7217229cd68a9d670ff28d7e3ecdbc42c77d55b6..4762196f55f4d9de313a297d9224c091511051eb 100644 (file)
@@ -18,6 +18,7 @@ import edu.wpi.first.math.geometry.Rotation2d;
 import edu.wpi.first.math.util.Units;
 import edu.wpi.first.wpilibj.RobotBase;
 import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim;
+import frc.robot.constants.Constants;
 import edu.wpi.first.wpilibj.smartdashboard.Mechanism2d;
 import edu.wpi.first.wpilibj.smartdashboard.MechanismLigament2d;
 import edu.wpi.first.wpilibj.smartdashboard.MechanismRoot2d;
@@ -159,7 +160,9 @@ public class Turret extends SubsystemBase implements TurretIO{
        @Override
        public void periodic() {
                updateInputs();
-               Logger.processInputs("Turret", inputs);
+               if (!Constants.DISABLE_LOGGING) {
+                       Logger.processInputs("Turret", inputs);
+               }
 
                // Position extrapolation
                double lookAheadSeconds = TurretConstants.EXTRAPOLATION_TIME_CONSTANT; 
@@ -216,14 +219,18 @@ public class Turret extends SubsystemBase implements TurretIO{
                        .withFeedForward(robotTurnCompensation));
                }
 
-        Logger.recordOutput("Turret/Voltage", motor.getMotorVoltage().getValue());
-               Logger.recordOutput("Turret/setpointDeg", goalAngle.getDegrees());
+        if (!Constants.DISABLE_LOGGING) {
+            Logger.recordOutput("Turret/Voltage", motor.getMotorVoltage().getValue());
+                       Logger.recordOutput("Turret/setpointDeg", goalAngle.getDegrees());
+        }
 
                // --- Visualization ---
                ligament.setAngle(Units.radiansToDegrees(getPositionRad()));
 
                updateInputs();
-               Logger.processInputs("Turret", inputs);
+               if (!Constants.DISABLE_LOGGING) {
+                       Logger.processInputs("Turret", inputs);
+               }
 
                SmartDashboard.putNumber("Turret position", Units.radiansToDegrees(getPositionRad()));
                SmartDashboard.putBoolean("Turret Calibrated", !calibrating);
index ad53fa7285bd1d57eb8b02022d8ddd8a24bdda58..4b184cb089345697c8075b639a7ba42d13b9f8d5 100644 (file)
@@ -32,6 +32,7 @@ import edu.wpi.first.networktables.NetworkTableInstance;
 import edu.wpi.first.wpilibj.DriverStation;
 import edu.wpi.first.wpilibj.RobotBase;
 import edu.wpi.first.wpilibj.Timer;
+import frc.robot.constants.Constants;
 import frc.robot.constants.FieldConstants;
 import frc.robot.constants.VisionConstants;
 import frc.robot.constants.swerve.DriveConstants;
@@ -546,7 +547,9 @@ public class Vision {
       inputs.connected = camera.isConnected();
       inputs.results = camera.getAllUnreadResults();
 
-      Logger.processInputs("Vision/"+camera.getName(), inputs);
+      if (!Constants.DISABLE_LOGGING) {
+        Logger.processInputs("Vision/"+camera.getName(), inputs);
+      }
 
       // Mechanical Advantage's vision logging
       // // Read new camera observations