From: Wesley28w Date: Fri, 3 Apr 2026 14:28:44 +0000 (-0700) Subject: I found every logger and made it enable only X-Git-Url: https://git.taranathan.com/?a=commitdiff_plain;h=ddcfe3237fe5d62c5a8d9df68bcbef4139787d6d;p=FRC2026.git I found every logger and made it enable only --- diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index f18a165..a1d15bc 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -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); })); } diff --git a/src/main/java/frc/robot/commands/LogCommand.java b/src/main/java/frc/robot/commands/LogCommand.java index e92bb5a..06b346d 100644 --- a/src/main/java/frc/robot/commands/LogCommand.java +++ b/src/main/java/frc/robot/commands/LogCommand.java @@ -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) { diff --git a/src/main/java/frc/robot/commands/drive_comm/DefaultDriveCommand.java b/src/main/java/frc/robot/commands/drive_comm/DefaultDriveCommand.java index 727a983..a99c5c6 100644 --- a/src/main/java/frc/robot/commands/drive_comm/DefaultDriveCommand.java +++ b/src/main/java/frc/robot/commands/drive_comm/DefaultDriveCommand.java @@ -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 { diff --git a/src/main/java/frc/robot/commands/gpm/AutoShootCommand.java b/src/main/java/frc/robot/commands/gpm/AutoShootCommand.java index 908c805..75a9ec1 100644 --- a/src/main/java/frc/robot/commands/gpm/AutoShootCommand.java +++ b/src/main/java/frc/robot/commands/gpm/AutoShootCommand.java @@ -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){ diff --git a/src/main/java/frc/robot/commands/gpm/Superstructure.java b/src/main/java/frc/robot/commands/gpm/Superstructure.java index 9da140f..e937cd7 100644 --- a/src/main/java/frc/robot/commands/gpm/Superstructure.java +++ b/src/main/java/frc/robot/commands/gpm/Superstructure.java @@ -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()); diff --git a/src/main/java/frc/robot/commands/vision/LogVision.java b/src/main/java/frc/robot/commands/vision/LogVision.java index da5e65f..2f9b8b2 100644 --- a/src/main/java/frc/robot/commands/vision/LogVision.java +++ b/src/main/java/frc/robot/commands/vision/LogVision.java @@ -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()); + } } } diff --git a/src/main/java/frc/robot/subsystems/drivetrain/Drivetrain.java b/src/main/java/frc/robot/subsystems/drivetrain/Drivetrain.java index dc50b47..4415c8a 100644 --- a/src/main/java/frc/robot/subsystems/drivetrain/Drivetrain.java +++ b/src/main/java/frc/robot/subsystems/drivetrain/Drivetrain.java @@ -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); } diff --git a/src/main/java/frc/robot/util/Vision/Vision.java b/src/main/java/frc/robot/util/Vision/Vision.java index 4b184cb..01825bc 100644 --- a/src/main/java/frc/robot/util/Vision/Vision.java +++ b/src/main/java/frc/robot/util/Vision/Vision.java @@ -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); + } }