Skip to content

Commit

Permalink
Some button bindings for testing
Browse files Browse the repository at this point in the history
  • Loading branch information
Bob1272001 committed Oct 23, 2024
1 parent c2f207f commit 6846074
Show file tree
Hide file tree
Showing 5 changed files with 55 additions and 24 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ public void robotInit() {
default:
Logger.recordMetadata("GitDirty", "Unknown");
break;
}
}

// Set up data receivers & replay source
switch (Constants.currentMode) {
Expand Down
51 changes: 33 additions & 18 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,8 @@
import frc.robot.subsystems.pivot.PivotIO;
import frc.robot.subsystems.pivot.PivotIOReal;
import frc.robot.subsystems.pivot.PivotIOSim;
import frc.robot.subsystems.shooter.Shooter;
import frc.robot.subsystems.shooter.ShooterIOReal;
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;

/**
Expand All @@ -48,6 +50,7 @@ public class RobotContainer {
private final Drive drive;
private final Intake intake;
private final Pivot pivot;
private final Shooter shooter;

// Controller
private final CommandXboxController controller = new CommandXboxController(0);
Expand All @@ -69,6 +72,7 @@ public RobotContainer() {
new ModuleIOTalonFX(3));
intake = Intake.initialize(new IntakeIOReal());
pivot = Pivot.initialize(new PivotIOReal());
shooter = Shooter.initialize(new ShooterIOReal());
break;

case SIM:
Expand All @@ -82,7 +86,7 @@ public RobotContainer() {
new ModuleIOSim());
intake = Intake.initialize(new IntakeIOSim());
pivot = Pivot.initialize(new PivotIOSim());

shooter = Shooter.initialize(new ShooterIOReal());
break;

default:
Expand All @@ -96,6 +100,7 @@ public RobotContainer() {
new ModuleIO() {});
intake = Intake.initialize(new IntakeIO() {});
pivot = Pivot.initialize(new PivotIO() {});
shooter = Shooter.initialize(new ShooterIOReal());
// change?
break;
}
Expand Down Expand Up @@ -132,23 +137,33 @@ private void configureButtonBindings() {
() -> -controller.getLeftX(),
() -> -controller.getRightX()));

controller.rightBumper()
.onTrue(Commands.run(() -> intake.setIntakeSpeed(0.75)))
.onFalse(Commands.run(() -> intake.setIntakeSpeed(0)));

controller.leftBumper()
.onTrue(Commands.run(() -> intake.setIntakeSpeed(-0.75)))
.onFalse(Commands.run(() -> intake.setIntakeSpeed(0)));

// controller
// .leftBumper()
// .whileTrue(Commands.startEnd(() -> pivot.runVoltage(3), () -> pivot.runVoltage(0),
// pivot));

// controller
// .rightBumper()
// .whileTrue(Commands.startEnd(() -> pivot.runVoltage(-3), () -> pivot.runVoltage(0),
// pivot));
controller
.rightTrigger()
.onTrue(Commands.run(() -> intake.setIntakeSpeed(0.75)))
.onFalse(Commands.run(() -> intake.setIntakeSpeed(0)));

controller
.leftTrigger()
.onTrue(Commands.run(() -> intake.setIntakeSpeed(-0.75)))
.onFalse(Commands.run(() -> intake.setIntakeSpeed(0)));

controller
.leftBumper()
.whileTrue(Commands.startEnd(() -> pivot.runVoltage(3), () -> pivot.runVoltage(0), pivot));
controller
.povUp()
.whileTrue(
Commands.startEnd(() -> shooter.setVoltage(6), () -> shooter.setVoltage(0), pivot));
// controller.leftBumper()
// .onTrue(Commands.runOnce(() -> pivot.runVoltage(3)))
// .onFalse(Commands.runOnce(() ->pivot.runVoltage(0), pivot));
// controller.rightBumper()
// .onTrue(Commands.runOnce(() -> pivot.runVoltage(3)))
// .onFalse(Commands.runOnce(() ->pivot.runVoltage(0), pivot));

controller
.rightBumper()
.whileTrue(Commands.startEnd(() -> pivot.runVoltage(-3), () -> pivot.runVoltage(0), pivot));

controller.a().whileTrue(Commands.runOnce(() -> drive.zeroHeading(), drive));
}
Expand Down
4 changes: 4 additions & 0 deletions src/main/java/frc/robot/subsystems/shooter/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,10 @@ private Shooter(ShooterIO shooterIO) {
io.updateInputs(inputs);
}

public void setVoltage(double voltage) {
io.setVoltage(voltage);
}

@Override
public void periodic() {
io.updateInputs(inputs);
Expand Down
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,5 +14,7 @@ public default void spinForwards() {}

public default void spinBackwards() {}

public default void setVoltage(double voltage) {}

public default void updateInputs(ShooterIOInputs inputs) {}
}
20 changes: 15 additions & 5 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIOReal.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,27 +6,37 @@

public class ShooterIOReal implements ShooterIO {
private CANSparkFlex leftShooterMotor =
new CANSparkFlex(0, MotorType.kBrushless); // Can IDs not accurate
new CANSparkFlex(3, MotorType.kBrushless); // Can IDs not accurate
private CANSparkFlex rightShooterMotor =
new CANSparkFlex(1, MotorType.kBrushless); // Can IDs not accurate
new CANSparkFlex(12, MotorType.kBrushless); // Can IDs not accurate
private RelativeEncoder leftShooterEncoder = leftShooterMotor.getEncoder();
private RelativeEncoder rightShooterEncoder = rightShooterMotor.getEncoder();

public ShooterIOReal() {
rightShooterMotor.follow(leftShooterMotor, true);
rightShooterMotor.restoreFactoryDefaults();
leftShooterMotor.restoreFactoryDefaults();
leftShooterMotor.follow(rightShooterMotor, true);

rightShooterMotor.setSmartCurrentLimit(40);
leftShooterMotor.setSmartCurrentLimit(40);

rightShooterMotor.burnFlash();
leftShooterMotor.burnFlash();
}

@Override
public void spinForwards() {
leftShooterMotor.set(1.0);
rightShooterMotor.set(1.0);
}

@Override
public void setVoltage(double voltage) {
rightShooterMotor.setVoltage(voltage);
}

@Override
public void spinBackwards() {
leftShooterMotor.set(-1.0);
rightShooterMotor.set(-1.0);
}

public double getLeftvelocity() {
Expand Down

0 comments on commit 6846074

Please sign in to comment.