From 4330ab07f46b20777baa64778ea4900df1eb0805 Mon Sep 17 00:00:00 2001 From: OlivierDubois Date: Mon, 5 Feb 2024 18:08:26 -0500 Subject: [PATCH] dashboard acc --- src/main/java/frc/robot/command/Balayer.java | 2 +- src/main/java/frc/robot/subsystem/Accumulateur.java | 10 +++++++++- 2 files changed, 10 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc/robot/command/Balayer.java b/src/main/java/frc/robot/command/Balayer.java index 31b57f1..61a1dc7 100644 --- a/src/main/java/frc/robot/command/Balayer.java +++ b/src/main/java/frc/robot/command/Balayer.java @@ -30,7 +30,7 @@ public class Balayer extends Command { } else{ balayeuse.balaye(0.6); - accumulateur.Accumuler(0.6); + accumulateur.Accumuler(); } } diff --git a/src/main/java/frc/robot/subsystem/Accumulateur.java b/src/main/java/frc/robot/subsystem/Accumulateur.java index fb3b646..82ade1e 100644 --- a/src/main/java/frc/robot/subsystem/Accumulateur.java +++ b/src/main/java/frc/robot/subsystem/Accumulateur.java @@ -6,6 +6,7 @@ package frc.robot.subsystem; import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; +import edu.wpi.first.networktables.GenericEntry; import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.Constants; @@ -17,7 +18,10 @@ import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout; public class Accumulateur extends SubsystemBase { /** Creates a new Accumulateur. */ - ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard"); + ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard"); + private GenericEntry vitesse = + dashboard.add("vitesseacc", 1) + .getEntry(); final WPI_TalonSRX Moteuracc2 = new WPI_TalonSRX(Constants.Moteuracc2); final WPI_TalonSRX Moteuracc = new WPI_TalonSRX(Constants.Moteuracc); final DigitalInput limitacc = new DigitalInput(Constants.limitacc); @@ -33,12 +37,16 @@ public class Accumulateur extends SubsystemBase { return limitacc.get(); } public Accumulateur() { + dashboard.addBoolean("limitacc", this::limitswitch); } public void Accumuler(double vitesse){ Moteuracc.set(vitesse); Moteuracc2.set(vitesse); } + public void Accumuler(){ + Accumuler(vitesse.getDouble(0.1)); + } @Override public void periodic() {