b
This commit is contained in:
parent
843e1cbb03
commit
9c9d821939
@ -79,6 +79,7 @@ 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));
|
||||||
|
manette.x().whileTrue(new PistonFerme(grimpeur));
|
||||||
joystick.button(3).whileTrue(new Balayer(balayeuse, accumulateur));
|
joystick.button(3).whileTrue(new Balayer(balayeuse, accumulateur));
|
||||||
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)));
|
||||||
|
@ -29,7 +29,7 @@ public class Balayer extends Command {
|
|||||||
accumulateur.Accumuler();
|
accumulateur.Accumuler();
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
balayeuse.balaye(0.6);
|
balayeuse.balaye(0.3);
|
||||||
accumulateur.Accumuler();
|
accumulateur.Accumuler();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -18,7 +18,7 @@ public class Accumulateur extends SubsystemBase {
|
|||||||
|
|
||||||
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
|
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
|
||||||
private GenericEntry vitesse =
|
private GenericEntry vitesse =
|
||||||
dashboard.add("vitesseacc", 1)
|
dashboard.add("vitesseacc", 0.1)
|
||||||
.withSize(1, 1)
|
.withSize(1, 1)
|
||||||
.withPosition(4, 3)
|
.withPosition(4, 3)
|
||||||
.getEntry();
|
.getEntry();
|
||||||
@ -41,11 +41,11 @@ 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.1));
|
Accumuler(vitesse.getDouble(0.3));
|
||||||
}
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
|
Loading…
x
Reference in New Issue
Block a user