ampréage dans le dashbord
This commit is contained in:
@@ -48,7 +48,7 @@ public class Aspirer extends Command {
|
|||||||
moyenneAmp += balayeuse.Amp() / nbFois;
|
moyenneAmp += balayeuse.Amp() / nbFois;
|
||||||
temp = balayeuse.Amp();
|
temp = balayeuse.Amp();
|
||||||
}
|
}
|
||||||
if(moyenneAmp < 40){
|
if(moyenneAmp < balayeuse.AmpMax()){
|
||||||
timer.reset();
|
timer.reset();
|
||||||
balayeuse.Balayer(0.5);
|
balayeuse.Balayer(0.5);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -59,7 +59,7 @@ public class Lancer extends Command {
|
|||||||
moyenneAmp += balayeuse.Amp() / nbFois;
|
moyenneAmp += balayeuse.Amp() / nbFois;
|
||||||
temp = balayeuse.Amp();
|
temp = balayeuse.Amp();
|
||||||
}
|
}
|
||||||
if(moyenneAmp > 30 && nbFois > 10){
|
if(moyenneAmp > lanceur.AmpBas() && nbFois > 10){
|
||||||
timer.reset();
|
timer.reset();
|
||||||
balayeuse.Balayer(0.5);
|
balayeuse.Balayer(0.5);
|
||||||
led.Jaune2();
|
led.Jaune2();
|
||||||
|
|||||||
@@ -23,6 +23,8 @@ public class Balayeuse extends SubsystemBase {
|
|||||||
DigitalInput limit = new DigitalInput(0);
|
DigitalInput limit = new DigitalInput(0);
|
||||||
private GenericEntry EncodeurBalayeuse =
|
private GenericEntry EncodeurBalayeuse =
|
||||||
teb.add("Position bas balayeuse", 10).getEntry();
|
teb.add("Position bas balayeuse", 10).getEntry();
|
||||||
|
private GenericEntry AmpBaleyeuse =
|
||||||
|
teb.add("Ampérage Baleyeuse", 40).getEntry();
|
||||||
public void Balayer(double vitesse){
|
public void Balayer(double vitesse){
|
||||||
Balaye1.set(vitesse);
|
Balaye1.set(vitesse);
|
||||||
Balaye2.set(vitesse);
|
Balaye2.set(vitesse);
|
||||||
@@ -42,6 +44,9 @@ public class Balayeuse extends SubsystemBase {
|
|||||||
public double Amp(){
|
public double Amp(){
|
||||||
return Balaye2.getOutputCurrent();
|
return Balaye2.getOutputCurrent();
|
||||||
}
|
}
|
||||||
|
public double AmpMax(){
|
||||||
|
return AmpBaleyeuse.getDouble(40);
|
||||||
|
}
|
||||||
public void Temps(){
|
public void Temps(){
|
||||||
Timer timer = new Timer();
|
Timer timer = new Timer();
|
||||||
timer.start();
|
timer.start();
|
||||||
|
|||||||
@@ -19,6 +19,8 @@ public class Lanceur extends SubsystemBase {
|
|||||||
SparkFlex Demeleur = new SparkFlex(4, MotorType.kBrushless);
|
SparkFlex Demeleur = new SparkFlex(4, MotorType.kBrushless);
|
||||||
GenericEntry vitesse =
|
GenericEntry vitesse =
|
||||||
teb.add("vitesse lanceur",100).getEntry();
|
teb.add("vitesse lanceur",100).getEntry();
|
||||||
|
GenericEntry AmpLanceur =
|
||||||
|
teb.add("ampérage lanceur",30).getEntry();
|
||||||
public void Lancer(double vitesse){
|
public void Lancer(double vitesse){
|
||||||
moteur1.set(vitesse);
|
moteur1.set(vitesse);
|
||||||
moteur2.set(-vitesse);
|
moteur2.set(-vitesse);
|
||||||
@@ -32,6 +34,9 @@ public class Lanceur extends SubsystemBase {
|
|||||||
public double Amp(){
|
public double Amp(){
|
||||||
return moteur1.getOutputCurrent();
|
return moteur1.getOutputCurrent();
|
||||||
}
|
}
|
||||||
|
public double AmpBas(){
|
||||||
|
return AmpLanceur.getDouble(30);
|
||||||
|
}
|
||||||
public double vitesseDemander(){
|
public double vitesseDemander(){
|
||||||
return vitesse.getDouble(100);
|
return vitesse.getDouble(100);
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user