4 moteur lanceur
This commit is contained in:
parent
27e57ca157
commit
83d20b577d
@ -9,14 +9,16 @@ public class Constants {
|
||||
//moteur
|
||||
public static int lanceur = 1;
|
||||
public static int lancer2 = 2;
|
||||
public static int roue = 3;
|
||||
public static int etoile = 4;
|
||||
public static int Moteuracc2 = 5;
|
||||
public static int Moteuracc = 6;
|
||||
public static int guideur = 7;
|
||||
public static int lanceur3 = 3;
|
||||
public static int lancer4 = 4;
|
||||
public static int roue = 5;
|
||||
public static int etoile = 6;
|
||||
public static int Moteuracc2 = 7;
|
||||
public static int Moteuracc = 8;
|
||||
public static int guideur = 9;
|
||||
// limit switsh
|
||||
public static int guideurhaut = 8;
|
||||
public static int guideurbas = 9;
|
||||
public static int limitacc = 58;
|
||||
public static int guideurhaut = 10;
|
||||
public static int guideurbas = 11;
|
||||
public static int limitacc = 12;
|
||||
|
||||
}
|
||||
|
@ -18,6 +18,8 @@ public class Lanceur extends SubsystemBase {
|
||||
public Lanceur() {}
|
||||
final CANSparkMax lancer = new CANSparkMax(Constants.lanceur, MotorType.kBrushless);
|
||||
final CANSparkMax lancer2 = new CANSparkMax(Constants.lancer2, MotorType.kBrushless);
|
||||
final CANSparkMax lancer3 = new CANSparkMax(Constants.lanceur, MotorType.kBrushless);
|
||||
final CANSparkMax lancer4 = new CANSparkMax(Constants.lancer2, MotorType.kBrushless);
|
||||
public void lancer(double vitesse){
|
||||
lancer.set(vitesse);
|
||||
}
|
||||
|
Loading…
x
Reference in New Issue
Block a user