diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 2c51cc7..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 = 0.2; // 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; diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index e402363..e58238e 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -388,6 +388,26 @@ 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) + // ============================== + + // 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))); new Trigger( () -> operatorController.getAButton()).onTrue( new InstantCommand(() -> selectedFixedTarget = FixedTarget.A)); 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);