From c093305a755f23953d6b177e77eb6cf20039915d Mon Sep 17 00:00:00 2001 From: Programming Date: Thu, 22 Feb 2024 16:18:42 -0800 Subject: [PATCH] feat: Fixed logic for setting and toggeling solenoids --- .../frc/robot/subsystems/ClimberSubsystem.java | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/ClimberSubsystem.java b/src/main/java/frc/robot/subsystems/ClimberSubsystem.java index cbff2b3..b5fe238 100644 --- a/src/main/java/frc/robot/subsystems/ClimberSubsystem.java +++ b/src/main/java/frc/robot/subsystems/ClimberSubsystem.java @@ -6,7 +6,10 @@ import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import frc.robot.Constants.ClimberConstants; + +import static edu.wpi.first.wpilibj.DoubleSolenoid.Value.kForward; import static edu.wpi.first.wpilibj.DoubleSolenoid.Value.kOff; +import static edu.wpi.first.wpilibj.DoubleSolenoid.Value.kReverse; public class ClimberSubsystem { @@ -43,8 +46,8 @@ public void off(){ * Extends both arms */ public void forward() { - m_leftSolenoid.set(kOff); - m_rightSolenoid.set(kOff); + m_leftSolenoid.set(kForward); + m_rightSolenoid.set(kForward); } //TODO:fix doc @@ -52,16 +55,16 @@ public void forward() { * Retracts the arm */ public void reverse() { - m_leftSolenoid.set(kOff); - m_rightSolenoid.set(kOff); + m_leftSolenoid.set(kReverse); + m_rightSolenoid.set(kReverse); } /* * Toggles the state of the climber */ public void toggle() { - m_leftSolenoid.set(kOff); - m_rightSolenoid.set(kOff); + m_leftSolenoid.toggle();; + m_rightSolenoid.toggle();; } //Toggles the state of the compressor (on/off)