From 046a5ba86d3e57e4676ad5516684bca725a51c46 Mon Sep 17 00:00:00 2001 From: Kavin Muralikrishnan Date: Sat, 30 Nov 2024 22:53:43 -0500 Subject: [PATCH] Update Pneumatics.java --- src/main/java/frc/robot/subsystems/Pneumatics.java | 14 +++++--------- 1 file changed, 5 insertions(+), 9 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/Pneumatics.java b/src/main/java/frc/robot/subsystems/Pneumatics.java index bf25dfc..c6085c3 100644 --- a/src/main/java/frc/robot/subsystems/Pneumatics.java +++ b/src/main/java/frc/robot/subsystems/Pneumatics.java @@ -1,29 +1,25 @@ package frc.robot.subsystems; -import edu.wpi.first.wpilibj.Compressor; import edu.wpi.first.wpilibj.DoubleSolenoid; import frc.robot.Constants.PneumaticConstants; import edu.wpi.first.wpilibj.PneumaticsModuleType; import edu.wpi.first.wpilibj2.command.SubsystemBase; public class Pneumatics extends SubsystemBase { - DoubleSolenoid m_doubleSolenoid = new DoubleSolenoid(PneumaticsModuleType.CTREPCM, - PneumaticConstants.kForwardChannel, PneumaticConstants.kReverseChannel); - Compressor m_compressor = new Compressor(PneumaticsModuleType.CTREPCM); - public Pneumatics() { - m_compressor.enableAnalog(100, 120); - } + DoubleSolenoid m_doubleSolenoid = new DoubleSolenoid(PneumaticsModuleType.CTREPCM, PneumaticConstants.kForwardChannel, + PneumaticConstants.kReverseChannel); + // may want to add a toggle option public void extendPiston() { m_doubleSolenoid.set(DoubleSolenoid.Value.kForward); } public void retractPiston() { - m_doubleSolenoid.set(DoubleSolenoid.Value.kForward); + m_doubleSolenoid.set(DoubleSolenoid.Value.kReverse); } public void setSolenoidOff() { - m_doubleSolenoid.set(DoubleSolenoid.Value.kForward); + m_doubleSolenoid.set(DoubleSolenoid.Value.kOff); } public void toggleSolenoid() {