diff --git a/src/main/java/frc/robot/subsystem/Lanceur.java b/src/main/java/frc/robot/subsystem/Lanceur.java index 9e457e4..db4e4bf 100644 --- a/src/main/java/frc/robot/subsystem/Lanceur.java +++ b/src/main/java/frc/robot/subsystem/Lanceur.java @@ -49,18 +49,10 @@ public class Lanceur extends SubsystemBase { // Mutable holder for unit-safe linear velocity values, persisted to avoid reallocation. private final MutableMeasure> velocity = mutable(RotationsPerSecond.of(0)); public void pidspeaker(){ - lanceur1.getPIDController().setP(0.5); - lanceur1.getPIDController().setI(0.5); - lanceur1.getPIDController().setD(0.5); - lanceur2.getPIDController().setP(0.5); - lanceur2.getPIDController().setI(0.5); - lanceur2.getPIDController().setD(0.5); - lanceur3.getPIDController().setP(0.5); - lanceur3.getPIDController().setI(0.5); - lanceur3.getPIDController().setD(0.5); - lanceur4.getPIDController().setP(0.5); - lanceur4.getPIDController().setI(0.5); - lanceur4.getPIDController().setD(0.5); + lanceur1.getPIDController().setP(0.000006824); + lanceur2.getPIDController().setP(0.0051335); + lanceur3.getPIDController().setP(0.00079046); + lanceur4.getPIDController().setP(0.0000049791); } private final SysIdRoutine sysIdRoutine = new SysIdRoutine(