From 84d23df96f28522b953b783ecabead2d970a66e8 Mon Sep 17 00:00:00 2001 From: OlivierDubois Date: Tue, 24 Oct 2023 18:05:43 -0400 Subject: [PATCH] changer spark a talon accumulateur --- .../frc/robot/subsystems/Accumulateur.java | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/Accumulateur.java b/src/main/java/frc/robot/subsystems/Accumulateur.java index 78fc270..3437c27 100644 --- a/src/main/java/frc/robot/subsystems/Accumulateur.java +++ b/src/main/java/frc/robot/subsystems/Accumulateur.java @@ -4,14 +4,15 @@ package frc.robot.subsystems; -import com.revrobotics.CANSparkMax; -import com.revrobotics.CANSparkMaxLowLevel.MotorType; +import edu.wpi.first.wpilibj.Encoder; +import edu.wpi.first.wpilibj.motorcontrol.Talon; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.Constants; public class Accumulateur extends SubsystemBase { - private CANSparkMax moteuracc = new CANSparkMax(Constants.accumulateur, MotorType.kBrushless); + private Talon moteuracc = new Talon(Constants.accumulateur); + /** Creates a new Accumulateur. */ public Accumulateur() { @@ -19,12 +20,12 @@ 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 double distance() { + // return(moteuracc.getEncoder().getPosition()); + // } + //public void Reset() { + // moteuracc.getEncoder().setPosition(0); + // } @Override public void periodic() { // This method will be called once per scheduler run