This commit is contained in:
Antoine PerreaultE 2024-02-17 13:06:16 -05:00
parent 843e1cbb03
commit bf6b877d37
6 changed files with 23 additions and 29 deletions

View File

@ -13,11 +13,11 @@ public class Constants {
public static int lancer4 = 15; public static int lancer4 = 15;
// Ballayeuse // Ballayeuse
public static int roue = 16; public static int roue = 16;
public static int etoile = 19; public static int etoile = 21;
// Accumulateur // Accumulateur
public static int Moteuracc2 = 20; public static int Moteuracc2 = 20;
public static int Moteuracc = 21; public static int Moteuracc = 19;
// Guideur // Guideur
public static int guideur = 22; public static int guideur = 22;
@ -43,8 +43,8 @@ public class Constants {
public static int ArriereGauche = 6; public static int ArriereGauche = 6;
// Limit switch // Limit switch
public static int guideurhaut = 0; public static int guideurhaut = 4;
public static int guideurbas = 1; public static int guideurbas = 5;
public static int photocellacc = 2; public static int photocellacc = 2;
public static int limithaut = 4; public static int limithaut = 4;
public static int limitbas = 5; public static int limitbas = 5;

View File

@ -26,10 +26,10 @@ public class Balayer extends Command {
public void execute() { public void execute() {
if(accumulateur.limitswitch()){ if(accumulateur.limitswitch()){
balayeuse.balaye(0); balayeuse.balaye(0);
accumulateur.Accumuler(); accumulateur.Accumuler(0);
} }
else{ else{
balayeuse.balaye(0.6); balayeuse.balaye(0.3);
accumulateur.Accumuler(); accumulateur.Accumuler();
} }
} }

View File

@ -26,10 +26,10 @@ public class LancerNote extends Command {
// Called every time the scheduler runs while the command is scheduled. // Called every time the scheduler runs while the command is scheduled.
@Override @Override
public void execute() { public void execute() {
double vitesse = 100; double vitesse = 0.5;
lancer.lancerspeaker(); lancer.lancerspeaker();
if(lancer.vitesse(vitesse)>vitesse){ if(lancer.vitesse(vitesse)>vitesse){
accumulateur.Accumuler(0.6); accumulateur.Accumuler();
} }
else{ else{
accumulateur.Accumuler(0); accumulateur.Accumuler(0);

View File

@ -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.5)
.withSize(1, 1) .withSize(1, 1)
.withPosition(4, 3) .withPosition(4, 3)
.getEntry(); .getEntry();
@ -27,11 +27,11 @@ public class Accumulateur extends SubsystemBase {
final DigitalInput photocellacc = new DigitalInput(Constants.photocellacc); final DigitalInput photocellacc = new DigitalInput(Constants.photocellacc);
public void Deaccumuler(double vitesse){ public void Deaccumuler(double vitesse){
Moteuracc2.set(vitesse); Moteuracc2.set(-vitesse);
Moteuracc.set(-vitesse);
} }
public void moteuraccfollow(){ public void moteuraccfollow(){
Moteuracc.follow(Moteuracc2);
Moteuracc.setInverted(true);
} }
public boolean limitswitch(){ public boolean limitswitch(){
return photocellacc.get(); return photocellacc.get();
@ -45,7 +45,7 @@ public class Accumulateur extends SubsystemBase {
Moteuracc2.set(vitesse); Moteuracc2.set(vitesse);
} }
public void Accumuler(){ public void Accumuler(){
Accumuler(vitesse.getDouble(0.1)); Accumuler(vitesse.getDouble(0.3));
} }
@Override @Override

View File

@ -15,13 +15,8 @@ public class Balayeuse extends SubsystemBase {
public Balayeuse() {} public Balayeuse() {}
final WPI_TalonSRX roue = new WPI_TalonSRX(Constants.roue); final WPI_TalonSRX roue = new WPI_TalonSRX(Constants.roue);
final WPI_TalonSRX etoile = new WPI_TalonSRX(Constants.etoile); final WPI_TalonSRX etoile = new WPI_TalonSRX(Constants.etoile);
public void Accumulation(double vitesse){
roue.set(vitesse);
}
public void balayeuse(){ public void balayeuse(){
etoile.follow(roue);
etoile.setInverted(true);
} }
public void balaye(double vitesse){ public void balaye(double vitesse){
roue.set(vitesse); roue.set(vitesse);

View File

@ -16,12 +16,12 @@ public class Lanceur extends SubsystemBase {
/** Creates a new Lanceur. */ /** Creates a new Lanceur. */
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard"); ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
private GenericEntry vitesse = private GenericEntry vitesse =
dashboard.add("vitesse", 1) dashboard.add("vitesse", 0.5)
.withSize(1, 1) .withSize(1, 1)
.withPosition(3, 3) .withPosition(3, 3)
.getEntry(); .getEntry();
private GenericEntry vitesseamp = private GenericEntry vitesseamp =
dashboard.add("vitesseamp", 1) dashboard.add("vitesseamp", 0.4)
.withSize(1, 1) .withSize(1, 1)
.withPosition(3, 4) .withPosition(3, 4)
.getEntry(); .getEntry();
@ -36,23 +36,22 @@ public class Lanceur extends SubsystemBase {
lanceur1.getPIDController(); lanceur1.getPIDController();
} }
public void lancer(double vitesse){ public void lancer(double vitesse){
lanceur1.set(vitesse); lanceur1.set(-vitesse);
lanceur2.set(-vitesse);
lanceur3.set(vitesse);
lanceur4.set(-vitesse);
} }
public void lancerspeaker(){ public void lancerspeaker(){
lancer(vitesse.getDouble(0.1)); lancer(vitesse.getDouble(0.5));
} }
public void lanceramp(){ public void lanceramp(){
lancer(vitesseamp.getDouble(0.5)); lancer(vitesseamp.getDouble(0.4));
} }
public double vitesse(double vitesse){ public double vitesse(double vitesse){
return lanceur1.getEncoder().getVelocity(); return lanceur1.getEncoder().getVelocity();
} }
public void lanceur(){ public void lanceur(){
lanceur2.follow(lanceur1);
lanceur3.follow(lanceur1);
lanceur4.follow(lanceur1);
lanceur3.setInverted(true);
lanceur4.setInverted(true);
} }
@Override @Override