From e7be1897006b8f8dfcf2253af5cfffbfb48b6797 Mon Sep 17 00:00:00 2001 From: "Jason M. Dudley" Date: Sat, 28 Mar 2026 14:59:29 -0500 Subject: [PATCH 1/5] Increase power offset rate. Add buttons to reset offsets. --- src/main/java/frc/robot/Constants.java | 2 +- src/main/java/frc/robot/RobotContainer.java | 24 +++++++++++++++++++++ 2 files changed, 25 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 2c51cc7..99ca347 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -58,7 +58,7 @@ public static class ErrorSettings { public static final int TURRET_OFFSET_DECIMAL_PLACE = 1; public static final double HOOD_OFFSET_INCREASE = 0.1; public static final int HOOD_OFFSET_DECIMAL_PLACE = 1; - public static final double SHOOTER_PERCENT_INCREASE = 0.2; // Percent to increase per tick + public static final double SHOOTER_PERCENT_INCREASE = 2; // Percent to increase per tick public static final int SHOOTER_PERCENT_DECIMAL_PLACE = 1; public static final double SHOOTER_PERCENT_DEFAULT = 100.0; diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index e402363..29ca267 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -388,6 +388,30 @@ public void configureBindings() { shooterPercent.getHeldIntervalCommand(Constants.Operator.ErrorSettings.SHOOTER_PERCENT_INCREASE, Constants.Operator.ErrorSettings.SETTINGS_DELAY_TIME)); + // ============================== + // Turret / Hood Offset Reset (Left Stick Click / Right Stick Click) + // ============================== + + // Left Stick Click : Reset turret offset to zero + new Trigger(() -> operatorController.getLeftStickButton()) + .onTrue(new InstantCommand(() -> turretOffsetDegrees.set(0.0))); + + // Right Stick Click : Reset hood offset to zero + new Trigger(() -> operatorController.getRightStickButton()) + .onTrue(new InstantCommand(() -> hoodOffsetDegrees.set(0.0))); + + // ============================== + // Shooter Percent Reset (Left Trigger / Right Trigger) + // ============================== + + // Left Trigger : Reset shooter percent to default + new Trigger(() -> operatorController.getLeftTriggerAxis() > 0.5) + .onTrue(new InstantCommand(() -> shooterPercent.set(Constants.Operator.ErrorSettings.SHOOTER_PERCENT_DEFAULT))); + + // Right Trigger : Reset shooter percent to default + new Trigger(() -> operatorController.getRightTriggerAxis() > 0.5) + .onTrue(new InstantCommand(() -> shooterPercent.set(Constants.Operator.ErrorSettings.SHOOTER_PERCENT_DEFAULT))); + new Trigger( () -> operatorController.getAButton()).onTrue( new InstantCommand(() -> selectedFixedTarget = FixedTarget.A)); From 249cb68a4b68e6455b728860f6a637a1dc748c98 Mon Sep 17 00:00:00 2001 From: "Jason M. Dudley" Date: Sat, 28 Mar 2026 15:03:06 -0500 Subject: [PATCH 2/5] Remove test comment --- src/main/java/frc/robot/subsystems/IntakePivotSubsystem.java | 1 - 1 file changed, 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/IntakePivotSubsystem.java b/src/main/java/frc/robot/subsystems/IntakePivotSubsystem.java index 7daf779..0926be7 100644 --- a/src/main/java/frc/robot/subsystems/IntakePivotSubsystem.java +++ b/src/main/java/frc/robot/subsystems/IntakePivotSubsystem.java @@ -15,7 +15,6 @@ import frc.robot.Configs; import frc.robot.Constants; -// Test public class IntakePivotSubsystem extends SubsystemBase { public TalonFX intake; private final PositionVoltage angleRequest = new PositionVoltage(0); From cc4c03480ec92fe70769b2a9cefe1609deae8344 Mon Sep 17 00:00:00 2001 From: "Jason M. Dudley" Date: Sat, 28 Mar 2026 15:15:42 -0500 Subject: [PATCH 3/5] Drop to 1 percent per tick for shooter percentage --- src/main/java/frc/robot/Constants.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 99ca347..1a3b8ca 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -58,7 +58,7 @@ public static class ErrorSettings { public static final int TURRET_OFFSET_DECIMAL_PLACE = 1; public static final double HOOD_OFFSET_INCREASE = 0.1; public static final int HOOD_OFFSET_DECIMAL_PLACE = 1; - public static final double SHOOTER_PERCENT_INCREASE = 2; // Percent to increase per tick + public static final double SHOOTER_PERCENT_INCREASE = 1; // Percent to increase per tick public static final int SHOOTER_PERCENT_DECIMAL_PLACE = 1; public static final double SHOOTER_PERCENT_DEFAULT = 100.0; From fc752159cd8c30666bbcbf1b22600312359ac43f Mon Sep 17 00:00:00 2001 From: "Jason M. Dudley" Date: Sat, 28 Mar 2026 15:29:05 -0500 Subject: [PATCH 4/5] Combine reset for both triggers into one command Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> --- src/main/java/frc/robot/RobotContainer.java | 10 +++------- 1 file changed, 3 insertions(+), 7 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 29ca267..e58238e 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -404,14 +404,10 @@ public void configureBindings() { // Shooter Percent Reset (Left Trigger / Right Trigger) // ============================== - // Left Trigger : Reset shooter percent to default - new Trigger(() -> operatorController.getLeftTriggerAxis() > 0.5) + // Either Trigger : Reset shooter percent to default + new Trigger(() -> operatorController.getLeftTriggerAxis() > 0.5 + || operatorController.getRightTriggerAxis() > 0.5) .onTrue(new InstantCommand(() -> shooterPercent.set(Constants.Operator.ErrorSettings.SHOOTER_PERCENT_DEFAULT))); - - // Right Trigger : Reset shooter percent to default - new Trigger(() -> operatorController.getRightTriggerAxis() > 0.5) - .onTrue(new InstantCommand(() -> shooterPercent.set(Constants.Operator.ErrorSettings.SHOOTER_PERCENT_DEFAULT))); - new Trigger( () -> operatorController.getAButton()).onTrue( new InstantCommand(() -> selectedFixedTarget = FixedTarget.A)); From 6fba5825a7727c0fa6b9a16a4026602fed27c820 Mon Sep 17 00:00:00 2001 From: "Jason M. Dudley" Date: Sat, 28 Mar 2026 15:54:21 -0500 Subject: [PATCH 5/5] 0.5 percent per 20 ms for shooter power --- src/main/java/frc/robot/Constants.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 1a3b8ca..5507c65 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -58,7 +58,7 @@ public static class ErrorSettings { public static final int TURRET_OFFSET_DECIMAL_PLACE = 1; public static final double HOOD_OFFSET_INCREASE = 0.1; public static final int HOOD_OFFSET_DECIMAL_PLACE = 1; - public static final double SHOOTER_PERCENT_INCREASE = 1; // Percent to increase per tick + public static final double SHOOTER_PERCENT_INCREASE = .5; // Percent to increase per tick public static final int SHOOTER_PERCENT_DECIMAL_PLACE = 1; public static final double SHOOTER_PERCENT_DEFAULT = 100.0;