Merge branch 'main' of https://git.demerso.net/PLS5618/pratique-2025
This commit is contained in:
commit
27ba15f95f
@ -27,6 +27,18 @@
|
||||
"waitTime": 2.0
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "lancer"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "wait",
|
||||
"data": {
|
||||
"waitTime": 1.0
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
@ -52,6 +64,18 @@
|
||||
"waitTime": 2.0
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "lancer"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "wait",
|
||||
"data": {
|
||||
"waitTime": 1.0
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
|
@ -35,6 +35,7 @@ public class RobotContainer {
|
||||
CommandXboxController manette = new CommandXboxController(0);
|
||||
public RobotContainer() {
|
||||
//NamedCommands.registerCommand("lancer", new Lancer(lanceur, accumulateur));
|
||||
//NamedCommands.registerCommand("Desaccumuler", new Desaccumuler(accumulateur));
|
||||
//autoChooser = AutoBuilder.buildAutoChooser();
|
||||
dashboard.addCamera("limelight3G", "limelight3G","limelight.local:5800")
|
||||
.withSize(3,4)
|
||||
|
@ -23,10 +23,12 @@ 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);
|
||||
final DigitalInput photocell2 = new DigitalInput(27);
|
||||
public void encodeur(){
|
||||
}
|
||||
public boolean photocell(){
|
||||
@ -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(2);
|
||||
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(3);
|
||||
@ -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