From 71b4e949981ec17f728d1712fb92af2b4f7501b4 Mon Sep 17 00:00:00 2001 From: EldraziSquirrel Date: Tue, 20 Feb 2024 13:48:48 -0500 Subject: [PATCH] Pneumatics --- src/main/java/frc/robot/subsystems/ClimbSubsystem.java | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/ClimbSubsystem.java b/src/main/java/frc/robot/subsystems/ClimbSubsystem.java index d0a60e9..38b28e3 100644 --- a/src/main/java/frc/robot/subsystems/ClimbSubsystem.java +++ b/src/main/java/frc/robot/subsystems/ClimbSubsystem.java @@ -4,6 +4,8 @@ import com.revrobotics.ControlType; import com.revrobotics.SparkPIDController; import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.wpilibj.PneumaticsModuleType; +import edu.wpi.first.wpilibj.Solenoid; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.Robot; import frc.robot.StateControllerSub; @@ -57,7 +59,9 @@ public ClimbSubsystem(StateControllerSub stateControllerSub) { climbFollower.burnFlash(); } + private final Solenoid m_solenoid = new Solenoid(PneumaticsModuleType.REVPH, 0); + static final double maxClawDistanceMeters = 0.50;//TODO: find this double setpointMeters = 0.0;//bottom double simMeters = 0.0; @@ -94,10 +98,10 @@ public double getClawPosition(){ } void extendPneumatic(){ - //TODO: make arm go to stowed position + m_solenoid.set(true); } void retractPneumatic(){ - //TODO: make arm go to ready position + m_solenoid.set( false); } void extendClaw(){