commit
This commit is contained in:
parent
36c15844b1
commit
f890ec4daa
@ -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);
|
||||
}
|
||||
|
||||
|
@ -18,11 +18,7 @@ public class Accumulateur extends SubsystemBase {
|
||||
|
||||
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
|
||||
private GenericEntry vitesse =
|
||||
<<<<<<< HEAD
|
||||
dashboard.add("vitesseacc", 0.1)
|
||||
=======
|
||||
dashboard.add("vitesseacc", 0.5)
|
||||
>>>>>>> 9d55ab9afa804a6ffb304aee298f28ad470c396d
|
||||
.withSize(1, 1)
|
||||
.withPosition(4, 3)
|
||||
.getEntry();
|
||||
|
@ -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(){
|
||||
|
||||
|
Loading…
x
Reference in New Issue
Block a user