This commit is contained in:
Olivier Dubois 2024-02-17 13:47:24 -05:00
commit e8855ae51b
2 changed files with 8 additions and 3 deletions

View File

@ -79,7 +79,8 @@ public class RobotContainer {
CameraServer.startAutomaticCapture(); CameraServer.startAutomaticCapture();
manette.a().whileTrue(new GuiderBas(guideur)); manette.a().whileTrue(new GuiderBas(guideur));
manette.b().whileTrue(new GuiderHaut(guideur)); manette.b().whileTrue(new GuiderHaut(guideur));
joystick.button(3).whileTrue(new Balayer(balayeuse, accumulateur)); manette.x().whileTrue(new PistonFerme(grimpeur));
joystick.button(3).whileTrue(balayer);
joystick.button(1).whileTrue(new LancerNote(lanceur, accumulateur)); joystick.button(1).whileTrue(new LancerNote(lanceur, accumulateur));
joystick.button(4).whileTrue(new ParallelCommandGroup(new Lancer(lanceur,limelight),new Limelight_tracker(limelight,drive))); joystick.button(4).whileTrue(new ParallelCommandGroup(new Lancer(lanceur,limelight),new Limelight_tracker(limelight,drive)));
joystick.button(2).whileTrue(new ParallelCommandGroup(new Lancerampli(lanceur,limelight),new Limelight_tracker(limelight,drive),new GuiderHaut(guideur))); joystick.button(2).whileTrue(new ParallelCommandGroup(new Lancerampli(lanceur,limelight),new Limelight_tracker(limelight,drive),new GuiderHaut(guideur)));

View File

@ -18,7 +18,11 @@ public class Accumulateur extends SubsystemBase {
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard"); ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
private GenericEntry vitesse = private GenericEntry vitesse =
<<<<<<< HEAD
dashboard.add("vitesseacc", 0.1)
=======
dashboard.add("vitesseacc", 0.5) dashboard.add("vitesseacc", 0.5)
>>>>>>> 9d55ab9afa804a6ffb304aee298f28ad470c396d
.withSize(1, 1) .withSize(1, 1)
.withPosition(4, 3) .withPosition(4, 3)
.getEntry(); .getEntry();
@ -41,8 +45,8 @@ public class Accumulateur extends SubsystemBase {
dashboard.addBoolean("limitacc", this::limitswitch); dashboard.addBoolean("limitacc", this::limitswitch);
} }
public void Accumuler(double vitesse){ public void Accumuler(double vitesse){
Moteuracc.set(vitesse); Moteuracc.set(-vitesse);
Moteuracc2.set(vitesse); Moteuracc2.set(-vitesse);
} }
public void Accumuler(){ public void Accumuler(){
Accumuler(vitesse.getDouble(0.3)); Accumuler(vitesse.getDouble(0.3));