From bf63394d77730cd1a09adf7865e6ddfa0e013710 Mon Sep 17 00:00:00 2001 From: OlivierDubois Date: Mon, 4 Nov 2024 18:24:47 -0500 Subject: [PATCH] dahboard --- src/main/java/frc/robot/Commands/Desaccumuler.java | 3 ++- .../java/frc/robot/Subsystems/Accumulateur.java | 8 +++----- src/main/java/frc/robot/Subsystems/Lanceur.java | 13 ++++++++++++- src/main/java/frc/robot/Subsystems/Limelight3G.java | 9 +++++++++ 4 files changed, 26 insertions(+), 7 deletions(-) diff --git a/src/main/java/frc/robot/Commands/Desaccumuler.java b/src/main/java/frc/robot/Commands/Desaccumuler.java index 68a79f7..71f5705 100644 --- a/src/main/java/frc/robot/Commands/Desaccumuler.java +++ b/src/main/java/frc/robot/Commands/Desaccumuler.java @@ -25,7 +25,8 @@ public class Desaccumuler extends Command { // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - accumulateur.desaccumule(0.1); + if(accumulateur.photocell()){accumulateur.desaccumule(0.1);} + } // Called once the command ends or is interrupted. diff --git a/src/main/java/frc/robot/Subsystems/Accumulateur.java b/src/main/java/frc/robot/Subsystems/Accumulateur.java index adb2996..2b2dc2c 100644 --- a/src/main/java/frc/robot/Subsystems/Accumulateur.java +++ b/src/main/java/frc/robot/Subsystems/Accumulateur.java @@ -16,9 +16,7 @@ import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; public class Accumulateur extends SubsystemBase { /** Creates a new Accumulateur. */ - public Accumulateur() {dashboard.addBoolean("photocellacc", this::limitswitch) - .withSize(1, 1) - .withPosition(0, 1); + public Accumulateur() {dashboard.addBoolean("photocellacc", this::photocell).withSize(1, 1).withPosition(0, 1); } ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard"); @@ -34,8 +32,8 @@ public class Accumulateur extends SubsystemBase { final DigitalInput photocell = new DigitalInput(94); public void encodeur(){ } - public boolean limitswitch(){ - return !photocell.get(); + public boolean photocell(){ + return photocell.get(); } public void desaccumule(double vitesse){ accumulateur1.set(vitesse); diff --git a/src/main/java/frc/robot/Subsystems/Lanceur.java b/src/main/java/frc/robot/Subsystems/Lanceur.java index b5fd79d..eec1a16 100644 --- a/src/main/java/frc/robot/Subsystems/Lanceur.java +++ b/src/main/java/frc/robot/Subsystems/Lanceur.java @@ -30,6 +30,11 @@ public class Lanceur extends SubsystemBase { .withSize(0,0) .withPosition(1, 4) .getEntry(); + private GenericEntry rotation = + dashboard.add("rottourel", 0.2) + .withSize(0,0) + .withPosition(1, 5) + .getEntry(); public void encodeur(double distance){ lanceur1.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative); lanceur2.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative); @@ -41,7 +46,7 @@ public class Lanceur extends SubsystemBase { lanceur2.setInverted(true); } public void lance(double vitesse){ - lanceur1.set(vitesse); + lanceur1.set(vitesse);lanceur2.set(vitesse); } public void lance(){ lance(vitesse.getDouble(0.2)); @@ -49,6 +54,12 @@ public class Lanceur extends SubsystemBase { public void tourelRotation(double x, double y, double rotation){ tourelle.set(rotation); } + public void tourelRotation(){ + tourelle.set(rotation.getDouble(0.1)); + } + public void vitesseTourel(){ + tourelle.set(0.1); + } public double distancetourel(){ return(tourelle.getEncoder().getPosition()); } diff --git a/src/main/java/frc/robot/Subsystems/Limelight3G.java b/src/main/java/frc/robot/Subsystems/Limelight3G.java index de2ad2a..866ee1f 100644 --- a/src/main/java/frc/robot/Subsystems/Limelight3G.java +++ b/src/main/java/frc/robot/Subsystems/Limelight3G.java @@ -6,10 +6,19 @@ package frc.robot.Subsystems; import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.net.PortForwarder; +import edu.wpi.first.networktables.GenericEntry; import edu.wpi.first.networktables.NetworkTable; import edu.wpi.first.networktables.NetworkTableEntry; import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; +import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; public class Limelight3G extends SubsystemBase { + ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard"); + private GenericEntry orientation = + dashboard.add("orientation tourel", 0.1) + .withSize(0, 0) + .withPosition(2, 4) + .getEntry(); NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight"); NetworkTableEntry tx = table.getEntry("tx");