Skip to content
This repository has been archived by the owner on Nov 13, 2024. It is now read-only.

Commit

Permalink
button mappings and shoot speed
Browse files Browse the repository at this point in the history
  • Loading branch information
PascalSkylake committed Mar 3, 2024
1 parent 1da4ecb commit 0907319
Show file tree
Hide file tree
Showing 5 changed files with 40 additions and 28 deletions.
28 changes: 14 additions & 14 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -167,16 +167,14 @@ private void configureXboxControllerBindings() {

/** Binds commands to the operator stick. */
private void configureOperatorStickBindings() {
// TODO: bind scoreSpeaker to use shooting math
Trigger scoreSpeaker = new Trigger(operatorStick::scoreSpeaker);
// scoreSpeaker.onTrue(new ShootSpeaker());
scoreSpeaker.onTrue(
Trigger shootManual = new Trigger(operatorStick::shootManual);
shootManual.onTrue(
new RampShooter(() -> 15)
.andThen(
new InstantCommand(() -> RobotContainer.shooter.feed(), RobotContainer.shooter)
)
);
scoreSpeaker.onFalse(new InstantCommand(() -> {
shootManual.onFalse(new InstantCommand(() -> {
RobotContainer.shooter.stopShooting();
RobotContainer.shooter.stopIndexer();
}, RobotContainer.shooter));
Expand Down Expand Up @@ -206,22 +204,24 @@ private void configureOperatorStickBindings() {

Trigger retractIntake = new Trigger(() -> operatorStick.retractIntake() && RobotContainer.arm.isArmClearingIntake());
retractIntake.onTrue(new SetIntakeState(IntakeState.kUp));

Trigger midIntake = new Trigger(operatorStick::midIntake);
midIntake.onTrue(new SetIntakeState(IntakeState.kMid));

Trigger intakeNoteSetpoint = new Trigger(() -> operatorStick.intakeNoteSetpoint());
intakeNoteSetpoint.onTrue(
Trigger handoffArm = new Trigger(operatorStick::handoffArm);
handoffArm.onTrue(
new SetIntakeState(IntakeState.kDown)
.andThen(new SetShooterState(ShooterState.kIntake).alongWith(new SetArmState(ArmState.kIntake)))
);

Trigger ampSetpoint = new Trigger(operatorStick::ampSetpoint);
ampSetpoint.onTrue(new SetArmState(ArmState.kAmp).alongWith(new SetShooterState(ShooterState.kAmp)));
Trigger ampArm = new Trigger(operatorStick::ampArm);
ampArm.onTrue(new SetArmState(ArmState.kAmp).alongWith(new SetShooterState(ShooterState.kAmp)));

// TODO: test subwoofer shot for auto then put this back to kShoot setpoint
Trigger shootSetpoint = new Trigger(() -> operatorStick.shootSetpoint() && RobotContainer.intake.isIntakeDown());
shootSetpoint.onTrue(new SetArmState(ArmState.kShootFromSubwoofer).alongWith(new SetShooterState(ShooterState.kShootFromSubwoofer)));
Trigger subwooferArm = new Trigger(() -> operatorStick.subwooferArm() && RobotContainer.intake.isIntakeDown());
subwooferArm.onTrue(new SetArmState(ArmState.kShootFromSubwoofer).alongWith(new SetShooterState(ShooterState.kShootFromSubwoofer)));

Trigger stowSetpoint = new Trigger(operatorStick::stowSetpoint);
stowSetpoint.onTrue(
Trigger stowArm = new Trigger(operatorStick::stowArm);
stowArm.onTrue(
(new SetArmState(ArmState.kStow).alongWith(new SetShooterState(ShooterState.kIntake)))
.andThen(new SetIntakeState(IntakeState.kUp))
);
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/shooter/ShootSpeaker.java
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ public class ShootSpeaker extends Command {
Alliance color;
boolean hasAlliance, hasNoteInitially;
double targetX, targetY, targetZ;
final double v0 = 20;
final double v0 = 15;
boolean goodTrajectory = true;
Timer timer;

Expand Down
34 changes: 23 additions & 11 deletions src/main/java/frc/robot/hid/OperatorStick.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ public boolean intakeNote() {
return getPOV() == 180;
}

public boolean scoreSpeaker() {
public boolean shootManual() {
return this.getRawButton(1);
}

Expand All @@ -25,26 +25,38 @@ public boolean scoreAmp() {
}

public boolean deployIntake() {
return this.getRawButton(5);
return this.getRawButton(16);
}

public boolean stowSetpoint() {
return this.getRawButton(7);
public boolean retractIntake() {
return this.getRawButton(14);
}

public boolean ampSetpoint() {
return this.getRawButton(8);
public boolean midIntake() {
return this.getRawButton(15);
}

public boolean shootSetpoint() {
return this.getRawButton(9);
public boolean ampArm() {
return this.getRawButton(5);
}

public boolean stowArm() {
return this.getRawButton(6);
}

public boolean intakeNoteSetpoint() {
public boolean handoffArm() {
return this.getRawButton(7);
}

public boolean subwooferArm() {
return this.getRawButton(10);
}

public boolean retractIntake() {
return this.getRawButton(11);
public boolean podiumArm() {
return this.getRawButton(9);
}

public boolean levelArm() {
return this.getRawButton(8);
}
}
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ public boolean hasNoteInside() {

public enum IntakeState {
kUp(0.44),
kMid(0.22),
kMid(0.2),
kDown(0);

public final double rotations;
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ public class Shooter extends SubsystemBase {
private final double SHOOTER_PIVOT_TO_END = 0.37516;
private final Translation3d SHOOTER_PIVOT_ROBOT_REL = new Translation3d(-0.2757, 0, 0.5972);

private final double v0 = 20;
private final double v0 = 15;

private final double kShooterP = 1;
private final double kShooterI = 0.01;
Expand Down

0 comments on commit 0907319

Please sign in to comment.