diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index dd9e541..84151d9 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -85,7 +85,9 @@ private void configureBindings() { .onTrue(new InstantCommand(() -> m_shooterSubsystem.spin(-0.75), m_shooterSubsystem)) .onFalse(new InstantCommand(() -> m_shooterSubsystem.spin(0), m_shooterSubsystem)); new JoystickButton(m_operatorController, Button.kA.value) - .onTrue(new InstantCommand(() -> m_climberSubsystem.toggle(), m_shooterSubsystem)); + .onTrue(new InstantCommand(() -> m_climberSubsystem.forward(), m_shooterSubsystem)); + new JoystickButton(m_operatorController, Button.kB.value) + .onTrue(new InstantCommand(() -> m_climberSubsystem.reverse(), m_shooterSubsystem)); } /** diff --git a/src/main/java/frc/robot/climberSubSystem.java b/src/main/java/frc/robot/climberSubSystem.java index 2c15183..39cfada 100644 --- a/src/main/java/frc/robot/climberSubSystem.java +++ b/src/main/java/frc/robot/climberSubSystem.java @@ -9,13 +9,14 @@ import static edu.wpi.first.wpilibj.DoubleSolenoid.Value.kOff; public class ClimberSubsystem { - // All + private final DoubleSolenoid m_leftSolenoid = new DoubleSolenoid(PneumaticsModuleType.REVPH, ClimberConstants.leftForwardChannel, ClimberConstants.leftReverseChannel); private final DoubleSolenoid m_rightSolenoid = new DoubleSolenoid(PneumaticsModuleType.REVPH, ClimberConstants.rightForwardChannel, ClimberConstants.rightReverseChannel); + private final Compressor m_compressor = new Compressor(PneumaticsModuleType.REVPH); + private boolean enableCompressor = true; - // public ClimberSubsystem(){ m_leftSolenoid.set(kOff); m_rightSolenoid.set(kOff);