diff --git a/src/main/java/frc/robot/command/LancerNote.java b/src/main/java/frc/robot/command/LancerNote.java index 8cc3a4a..1c32ce5 100644 --- a/src/main/java/frc/robot/command/LancerNote.java +++ b/src/main/java/frc/robot/command/LancerNote.java @@ -26,7 +26,7 @@ public class LancerNote extends Command { // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - double vitesse = 0.5; + double vitesse = 0.8; lancer.lancerspeaker(); if(lancer.vitesse(vitesse)>vitesse){ accumulateur.Accumuler(); @@ -39,7 +39,7 @@ public class LancerNote extends Command { // Called once the command ends or is interrupted. @Override public void end(boolean interrupted) { - lancer.vitesse(0); + lancer.lancer(0); accumulateur.Accumuler(0); } diff --git a/src/main/java/frc/robot/subsystem/Lanceur.java b/src/main/java/frc/robot/subsystem/Lanceur.java index bd4f7fc..7730b2b 100644 --- a/src/main/java/frc/robot/subsystem/Lanceur.java +++ b/src/main/java/frc/robot/subsystem/Lanceur.java @@ -16,12 +16,12 @@ public class Lanceur extends SubsystemBase { /** Creates a new Lanceur. */ ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard"); private GenericEntry vitesse = - dashboard.add("vitesse", 0.5) + dashboard.add("vitesse", 0.8) .withSize(1, 1) .withPosition(3, 3) .getEntry(); private GenericEntry vitesseamp = - dashboard.add("vitesseamp", 0.4) + dashboard.add("vitesseamp", 0.1) .withSize(1, 1) .withPosition(3, 4) .getEntry(); @@ -42,13 +42,13 @@ public class Lanceur extends SubsystemBase { lanceur4.set(-vitesse); } public void lancerspeaker(){ - lancer(vitesse.getDouble(0.5)); + lancer(vitesse.getDouble(0.8)); } public void lanceramp(){ - lancer(vitesseamp.getDouble(0.4)); + lancer(vitesseamp.getDouble(0.1)); } public double vitesse(double vitesse){ - return lanceur1.getEncoder().getVelocity(); + return lanceur3.getEncoder().getVelocity(); } public void lanceur(){