From 304fc76be8a9ccb0d85626e37b1e78463c4604d5 Mon Sep 17 00:00:00 2001 From: Antoine PerreaultE Date: Sat, 24 Feb 2024 13:43:50 -0500 Subject: [PATCH] g --- src/main/java/frc/robot/subsystem/Accumulateur.java | 2 +- src/main/java/frc/robot/subsystem/Drive.java | 2 +- src/main/java/frc/robot/subsystem/Lanceur.java | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/subsystem/Accumulateur.java b/src/main/java/frc/robot/subsystem/Accumulateur.java index e8d0b6b..4d68ad3 100644 --- a/src/main/java/frc/robot/subsystem/Accumulateur.java +++ b/src/main/java/frc/robot/subsystem/Accumulateur.java @@ -41,7 +41,7 @@ public class Accumulateur extends SubsystemBase { Moteuracc2.set(-vitesse); } public void Accumuler(){ - Accumuler(vitesse.getDouble(0.3)); + Accumuler(vitesse.getDouble(0.5)); } @Override diff --git a/src/main/java/frc/robot/subsystem/Drive.java b/src/main/java/frc/robot/subsystem/Drive.java index f25ec63..870322e 100644 --- a/src/main/java/frc/robot/subsystem/Drive.java +++ b/src/main/java/frc/robot/subsystem/Drive.java @@ -25,7 +25,7 @@ public class Drive extends SubsystemBase { File swerveJsonDirectory = new File(Filesystem.getDeployDirectory(),"swerve"); public void drive(double x, double y, double zRotation){ - swerveDrive.drive(new Translation2d(x*3, y*3), zRotation, true, false); + swerveDrive.drive(new Translation2d(x*3, y*3), zRotation*3, true, false); } public Drive() { diff --git a/src/main/java/frc/robot/subsystem/Lanceur.java b/src/main/java/frc/robot/subsystem/Lanceur.java index 91e2cbd..ce081fb 100644 --- a/src/main/java/frc/robot/subsystem/Lanceur.java +++ b/src/main/java/frc/robot/subsystem/Lanceur.java @@ -26,7 +26,7 @@ public class Lanceur extends SubsystemBase { /** Creates a new Lanceur. */ ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard"); private GenericEntry vitesse = - dashboard.add("vitesse", 0.8) + dashboard.add("vitesse", 0.9) .withSize(1, 1) .withPosition(2,0) .getEntry(); @@ -84,7 +84,7 @@ public class Lanceur extends SubsystemBase { lanceur4.set(-vitesse); } public void lancerspeaker(){ - lancer(vitesse.getDouble(0.8)); + lancer(vitesse.getDouble(0.9)); } public void Lancertrape(){ lancer(vitesse.getDouble(0.8));