roues rouges et bleus + Ids
This commit is contained in:
parent
dde21cddfd
commit
d709f194b4
@ -23,8 +23,10 @@ public class Accumulateur extends SubsystemBase {
|
||||
.withPosition(0, 0)
|
||||
.getEntry();
|
||||
|
||||
final WPI_TalonSRX strap = new WPI_TalonSRX(0);
|
||||
final WPI_TalonSRX roueRouge = new WPI_TalonSRX(10);
|
||||
final WPI_TalonSRX strap = new WPI_TalonSRX(16);
|
||||
final WPI_TalonSRX rouesbleues = new WPI_TalonSRX(21);
|
||||
final WPI_TalonSRX roueRouge1 = new WPI_TalonSRX(14);
|
||||
final WPI_TalonSRX roueRouge2 = new WPI_TalonSRX(22);
|
||||
final DigitalInput photocell = new DigitalInput(20);
|
||||
final DigitalInput photocell2 = new DigitalInput(21);
|
||||
public void encodeur(){
|
||||
@ -39,8 +41,15 @@ public class Accumulateur extends SubsystemBase {
|
||||
strap.set(vitesse);
|
||||
|
||||
}
|
||||
public void masterslave(){
|
||||
roueRouge2.follow(roueRouge1);
|
||||
roueRouge1.setInverted(true);
|
||||
}
|
||||
public void masterslave2(){
|
||||
rouesbleues.follow(strap);
|
||||
}
|
||||
public void Petitlanceur(double vitesse){
|
||||
roueRouge.set(vitesse);
|
||||
roueRouge1.set(vitesse);
|
||||
}
|
||||
|
||||
public void desaccumule(){
|
||||
|
@ -31,8 +31,8 @@ public class Lanceur extends SubsystemBase {
|
||||
}
|
||||
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
|
||||
|
||||
final WPI_TalonSRX lanceur1 = new WPI_TalonSRX(0);
|
||||
final WPI_TalonSRX lanceur2 = new WPI_TalonSRX(1);
|
||||
final WPI_TalonSRX lanceur1 = new WPI_TalonSRX(17);
|
||||
final WPI_TalonSRX lanceur2 = new WPI_TalonSRX(15);
|
||||
final CANSparkMax tourelle = new CANSparkMax(2, MotorType.kBrushless);
|
||||
final DigitalInput limitswitch1 = new DigitalInput(0);
|
||||
final DigitalInput limitswitch2 = new DigitalInput(1);
|
||||
@ -55,7 +55,7 @@ public class Lanceur extends SubsystemBase {
|
||||
}
|
||||
public void masterslave(){
|
||||
lanceur2.follow(lanceur1);
|
||||
lanceur2.setInverted(true);
|
||||
lanceur1.setInverted(true);
|
||||
}
|
||||
public void lance(double vitesse){
|
||||
lanceur1.set(vitesse);
|
||||
|
Loading…
x
Reference in New Issue
Block a user