Dashboard (je suis triste)
This commit is contained in:
parent
f3d93dddda
commit
05fc41d766
86
simgui.json
86
simgui.json
@ -1,99 +1,13 @@
|
||||
{
|
||||
"HALProvider": {
|
||||
"Other Devices": {
|
||||
"SPARK MAX [10]": {
|
||||
"header": {
|
||||
"open": true
|
||||
}
|
||||
},
|
||||
"SPARK MAX [13]": {
|
||||
"header": {
|
||||
"open": true
|
||||
}
|
||||
},
|
||||
"SPARK MAX [14]": {
|
||||
"header": {
|
||||
"open": true
|
||||
}
|
||||
},
|
||||
"SPARK MAX [15]": {
|
||||
"header": {
|
||||
"open": true
|
||||
}
|
||||
}
|
||||
},
|
||||
<<<<<<< HEAD
|
||||
"Solenoids": {
|
||||
"window": {
|
||||
"visible": true
|
||||
}
|
||||
},
|
||||
=======
|
||||
>>>>>>> 88c4a9552f1a0b19d806a7672f738c1a9b60846b
|
||||
"Timing": {
|
||||
"window": {
|
||||
"visible": false
|
||||
}
|
||||
}
|
||||
},
|
||||
"NTProvider": {
|
||||
"types": {
|
||||
"/FMSInfo": "FMSInfo",
|
||||
"/Shuffleboard/dashboard/autochooser": "String Chooser",
|
||||
"/SmartDashboard/Field": "Field2d",
|
||||
"/SmartDashboard/Pigeon IMU [0]": "Gyro"
|
||||
},
|
||||
"windows": {
|
||||
"/Shuffleboard/dashboard/autochooser": {
|
||||
"window": {
|
||||
"visible": true
|
||||
}
|
||||
},
|
||||
"/SmartDashboard/Field": {
|
||||
"bottom": 1476,
|
||||
"height": 8.210550308227539,
|
||||
"left": 150,
|
||||
"right": 2961,
|
||||
"top": 79,
|
||||
"width": 16.541748046875,
|
||||
"window": {
|
||||
"visible": true
|
||||
}
|
||||
}
|
||||
}
|
||||
},
|
||||
"NetworkTables": {
|
||||
"transitory": {
|
||||
"SmartDashboard": {
|
||||
"Field": {
|
||||
"open": true
|
||||
},
|
||||
"open": true
|
||||
}
|
||||
}
|
||||
},
|
||||
"NetworkTables Info": {
|
||||
"visible": true
|
||||
},
|
||||
"NetworkTables View": {
|
||||
"visible": false
|
||||
},
|
||||
"Plot": {
|
||||
"Plot <0>": {
|
||||
"plots": [
|
||||
{
|
||||
"backgroundColor": [
|
||||
0.0,
|
||||
0.0,
|
||||
0.0,
|
||||
0.8500000238418579
|
||||
],
|
||||
"height": 332
|
||||
}
|
||||
],
|
||||
"window": {
|
||||
"visible": false
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -71,13 +71,18 @@ public class RobotContainer {
|
||||
AllumeLED allumeLED = new AllumeLED(LED, accumulateur);
|
||||
Pistongrimpeur pistongrimpeur = new Pistongrimpeur(grimpeur, LED);
|
||||
public RobotContainer() {
|
||||
dashboard.addCamera("limelight", "limelight","limelight.local:5800");
|
||||
dashboard.addCamera("limelight", "limelight","limelight.local:5800")
|
||||
.withSize(3,4)
|
||||
.withPosition(7,0);
|
||||
NamedCommands.registerCommand("balayer",new Balayer(balayeuse, accumulateur));
|
||||
NamedCommands.registerCommand("lancer", new LancerNote(lanceur, accumulateur));
|
||||
NamedCommands.registerCommand("piston", new PistonFerme(grimpeur));
|
||||
autoChooser = AutoBuilder.buildAutoChooser();
|
||||
|
||||
CameraServer.startAutomaticCapture();
|
||||
dashboard.addCamera("USB Camera 0", "USB Camera 0","http://roborio-5618-frc.local:1181/?action=stream")
|
||||
.withSize(4, 4)
|
||||
.withPosition(3, 0);
|
||||
|
||||
manette.a().whileTrue(new GuiderBas(guideur));
|
||||
manette.b().whileTrue(new GuiderHaut(guideur));
|
||||
manette.x().whileTrue(new PistonFerme(grimpeur));
|
||||
@ -103,7 +108,7 @@ public class RobotContainer {
|
||||
LED.setDefaultCommand(allumeLED);
|
||||
dashboard.add("autochooser",autoChooser)
|
||||
.withSize(2,1)
|
||||
.withPosition(1,1);
|
||||
.withPosition(0,1);
|
||||
}
|
||||
|
||||
private void configureBindings() {}
|
||||
|
@ -38,7 +38,7 @@ public class LancerAmp extends Command {
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
lancer.lancer(0);
|
||||
lancer.lanceramp();
|
||||
accumulateur.Accumuler(0);
|
||||
}
|
||||
|
||||
|
@ -20,7 +20,7 @@ public class Accumulateur extends SubsystemBase {
|
||||
private GenericEntry vitesse =
|
||||
dashboard.add("vitesseacc", 0.5)
|
||||
.withSize(1, 1)
|
||||
.withPosition(4, 3)
|
||||
.withPosition(2, 2)
|
||||
.getEntry();
|
||||
final WPI_TalonSRX Moteuracc2 = new WPI_TalonSRX(Constants.Moteuracc2);
|
||||
final WPI_TalonSRX Moteuracc = new WPI_TalonSRX(Constants.Moteuracc);
|
||||
@ -32,7 +32,9 @@ public class Accumulateur extends SubsystemBase {
|
||||
}
|
||||
public Accumulateur() {
|
||||
|
||||
dashboard.addBoolean("limitacc", this::limitswitch);
|
||||
dashboard.addBoolean("limitacc", this::limitswitch)
|
||||
.withSize(1, 1)
|
||||
.withPosition(2, 0);
|
||||
}
|
||||
public void Accumuler(double vitesse){
|
||||
Moteuracc.set(-vitesse);
|
||||
|
@ -23,8 +23,8 @@ public class Grimpeur extends SubsystemBase {
|
||||
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
|
||||
ShuffleboardLayout layout = Shuffleboard.getTab("dashboard")
|
||||
.getLayout("grimpeur", BuiltInLayouts.kList)
|
||||
.withSize(2,4)
|
||||
.withPosition(2,1);
|
||||
.withSize(2,2)
|
||||
.withPosition(0,2);
|
||||
final CANSparkMax grimpeurd = new CANSparkMax(Constants.grimpeurd,MotorType.kBrushless);
|
||||
final CANSparkMax grimpeurg = new CANSparkMax(Constants.grimpeurg,MotorType.kBrushless);
|
||||
// limit switch
|
||||
|
@ -16,16 +16,17 @@ public class Guideur extends SubsystemBase {
|
||||
/** Creates a new Guideur. */
|
||||
|
||||
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
|
||||
ShuffleboardLayout layout = Shuffleboard.getTab("dashboard")
|
||||
.getLayout("grimpeur")
|
||||
.withSize(2, 2)
|
||||
.withPosition(1, 3);
|
||||
|
||||
final WPI_TalonSRX guideur = new WPI_TalonSRX(Constants.guideur);
|
||||
final DigitalInput guideurhaut = new DigitalInput(Constants.guideurhaut);
|
||||
final DigitalInput guideurbas = new DigitalInput(Constants.guideurbas);
|
||||
public Guideur() {
|
||||
dashboard.addBoolean("limitguideurhaut", guideurhaut::get);
|
||||
dashboard.addBoolean("limitguideurbas", guideurbas::get);
|
||||
dashboard.addBoolean("limitguideurhaut", guideurhaut::get)
|
||||
.withSize(1,1)
|
||||
.withPosition(0,0);
|
||||
dashboard.addBoolean("limitguideurbas", guideurbas::get)
|
||||
.withSize(1,1)
|
||||
.withPosition(1,0);
|
||||
}
|
||||
public void guider(double vitesse){
|
||||
guideur.set(vitesse);
|
||||
|
@ -18,12 +18,12 @@ public class Lanceur extends SubsystemBase {
|
||||
private GenericEntry vitesse =
|
||||
dashboard.add("vitesse", 0.8)
|
||||
.withSize(1, 1)
|
||||
.withPosition(3, 3)
|
||||
.withPosition(2,1)
|
||||
.getEntry();
|
||||
private GenericEntry vitesseamp =
|
||||
dashboard.add("vitesseamp", 0.1)
|
||||
.withSize(1, 1)
|
||||
.withPosition(3, 4)
|
||||
.withPosition(2,3)
|
||||
.getEntry();
|
||||
public Lanceur() {
|
||||
|
||||
|
Loading…
x
Reference in New Issue
Block a user