From 30bdf2d26813834a3b1d1cd290611bc7cdf1d4e3 Mon Sep 17 00:00:00 2001 From: Gold87 <91761103+Gold872@users.noreply.github.com> Date: Wed, 11 Mar 2026 22:52:48 -0400 Subject: [PATCH 1/2] Add logging for power distribution --- src/main/java/frc/robot/RobotContainer.java | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 1025a93..5d7e9da 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -16,6 +16,7 @@ import edu.wpi.first.math.filter.Debouncer; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.wpilibj.GenericHID.RumbleType; +import edu.wpi.first.wpilibj.PowerDistribution; import edu.wpi.first.wpilibj.RobotBase; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; @@ -106,6 +107,8 @@ public class RobotContainer { private final SwerveTelemetry swerveTelemetry = new SwerveTelemetry(); + private final PowerDistribution powerDistribution = new PowerDistribution(); + private Debouncer kickerLaserDebouncer = new Debouncer(2.0); Trigger kickerLaserTrigger = new Trigger(() -> spindexer.kickerLaserBroken()); @@ -249,6 +252,8 @@ public RobotContainer() { configureFuelSim(); } + SmartDashboard.putData("Power Distribution", powerDistribution); + SmartDashboard.putData( "Set Arm Down", intake.runOnce(() -> intake.setArmMaxPosition()).ignoringDisable(true)); SmartDashboard.putData( From 5dafe831e5022db922b26a5086095768b4007a55 Mon Sep 17 00:00:00 2001 From: Gold87 <91761103+Gold872@users.noreply.github.com> Date: Thu, 12 Mar 2026 23:24:38 -0400 Subject: [PATCH 2/2] formatting --- src/main/java/frc/robot/RobotContainer.java | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 0887844..c5bcee9 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -15,9 +15,9 @@ import edu.wpi.first.epilogue.Logged; import edu.wpi.first.math.filter.Debouncer; import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.GenericHID.RumbleType; import edu.wpi.first.wpilibj.PowerDistribution; -import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.RobotBase; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; @@ -290,8 +290,14 @@ public RobotContainer() { preShiftShoot.onTrue(Commands.runOnce(() -> canPreShoot = true)); activeHubTrigger.onFalse(Commands.runOnce(() -> canPreShoot = false)); - shiftEndingTrigger.onTrue(driverController.rumbleFor(RumbleType.kBothRumble, 1.0, 3).onlyIf(()-> DriverStation.isTeleop())); - shiftEndingTrigger.onTrue(operatorController.rumbleFor(RumbleType.kBothRumble, 1.0, 3).onlyIf(()-> DriverStation.isTeleop())); + shiftEndingTrigger.onTrue( + driverController + .rumbleFor(RumbleType.kBothRumble, 1.0, 3) + .onlyIf(() -> DriverStation.isTeleop())); + shiftEndingTrigger.onTrue( + operatorController + .rumbleFor(RumbleType.kBothRumble, 1.0, 3) + .onlyIf(() -> DriverStation.isTeleop())); } private void configureFuelSim() {