Skip to content

Commit

Permalink
amp update
Browse files Browse the repository at this point in the history
  • Loading branch information
xorbotz committed Jan 29, 2024
1 parent 8660b58 commit dc8c481
Show file tree
Hide file tree
Showing 3 changed files with 13 additions and 9 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ public static final class Shooter {
public static final double voltageComp = 16.0;

public static final int speakerStrength = 10000;
public static final int ampStrength = 2560;
public static final double ampStrength = .095;
public static final int receive = 100;

}
Expand Down
5 changes: 5 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,11 @@ private void configureButtonBindings() {
new JoystickButton(OPERATOR, 6)
.whileTrue(
new RunCommand(() -> ShooterSubsystem.bump(true), ShooterSubsystem));

new JoystickButton(OPERATOR, 10)
.whileTrue(
new RunCommand(() -> ShooterSubsystem.ampShot(true), ShooterSubsystem));

}

public Command getAutonomousCommand() {
Expand Down
15 changes: 7 additions & 8 deletions src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -105,19 +105,18 @@ public void speakerShot(boolean shoot) {

public void ampShot(boolean shoot) {
if (shoot) {
shooterPidController_1.setReference(
Constants.Shooter.ampStrength,
ControlType.kVelocity);
shooterPidController_2.setReference(
Constants.Shooter.ampStrength,
ControlType.kVelocity);
shooterMotor_1.set(Constants.Shooter.ampStrength);
shooterMotor_2.set(Constants.Shooter.ampStrength-.025);
} else {
shooterPidController_1.setReference(
Constants.Shooter.ampStrength,
0,
ControlType.kVelocity);
shooterMotor_1.set(0);
shooterPidController_2.setReference(
Constants.Shooter.ampStrength,
0,
ControlType.kVelocity);
shooterMotor_2.set(0);
bumpMotor.set(0);
}
}
public void receive(boolean shoot) {
Expand Down

0 comments on commit dc8c481

Please sign in to comment.