From 202b0b7b7e24d54180807dc90c008c146e9128d0 Mon Sep 17 00:00:00 2001 From: OlivierDubois Date: Tue, 24 Oct 2023 18:53:22 -0400 Subject: [PATCH] limit + encodeur accumulateur --- .../frc/robot/subsystems/Accumulateur.java | 23 +++++++++++-------- 1 file changed, 13 insertions(+), 10 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/Accumulateur.java b/src/main/java/frc/robot/subsystems/Accumulateur.java index 8e9a8a9..823e9e0 100644 --- a/src/main/java/frc/robot/subsystems/Accumulateur.java +++ b/src/main/java/frc/robot/subsystems/Accumulateur.java @@ -5,17 +5,15 @@ package frc.robot.subsystems; -import com.ctre.phoenix.motorcontrol.can.TalonSRX; import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; -import edu.wpi.first.wpilibj.Encoder; -import edu.wpi.first.wpilibj.motorcontrol.Talon; +import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.Constants; public class Accumulateur extends SubsystemBase { private WPI_TalonSRX moteuracc = new WPI_TalonSRX(Constants.accumulateur); - + private DigitalInput limitacc = new DigitalInput(Constants.ballon); /** Creates a new Accumulateur. */ public Accumulateur() { @@ -23,12 +21,17 @@ public class Accumulateur extends SubsystemBase { public void Deaccumuler(double vitesse){ moteuracc.set(vitesse); } - //public double distance() { - // return(moteuracc.getEncoder().getPosition()); - // } - //public void Reset() { - // moteuracc.getEncoder().setPosition(0); - // } + + public boolean limit(){ + return limitacc.get(); + } + + public double distance() { + return(moteuracc.getSelectedSensorPosition()); + } + public void Reset() { + moteuracc.setSelectedSensorPosition(0); + } @Override public void periodic() { // This method will be called once per scheduler run