diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index fe07cb5..dea7d5a 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -5,6 +5,10 @@ public class Constants { public static int avantgauche = 1; public static int arrieredroit = 2; public static int arrieregauche = 3; + // pneumatique + public static int pistonpinceouvre = 0; + public static int pistonpinceferme = 1; + diff --git a/src/main/java/frc/robot/subsystems/bras/Pince.java b/src/main/java/frc/robot/subsystems/bras/Pince.java index a77e8a2..03e643c 100644 --- a/src/main/java/frc/robot/subsystems/bras/Pince.java +++ b/src/main/java/frc/robot/subsystems/bras/Pince.java @@ -4,14 +4,28 @@ package frc.robot.subsystems.bras; +import edu.wpi.first.wpilibj.DoubleSolenoid; +import edu.wpi.first.wpilibj.PneumaticsModuleType; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import edu.wpi.first.wpilibj.DoubleSolenoid.Value; +import frc.robot.Constants; public class Pince extends SubsystemBase { + private DoubleSolenoid pistonPince = new DoubleSolenoid(PneumaticsModuleType.CTREPCM,Constants.pistonpinceouvre, Constants.pistonpinceferme); /** Creates a new Pince. */ - public Pince() {} + public Pince() { + + } +public void fermer() { + pistonPince.set(Value.kReverse); + + } + public void ouvrir() { + pistonPince.set(Value.kForward); + } @Override public void periodic() { - // This method will be called once per scheduler run + } }