diff --git a/src/main/deploy/swerve/modules/backright.json b/src/main/deploy/swerve/modules/backright.json index a2b0c92..9c88523 100644 --- a/src/main/deploy/swerve/modules/backright.json +++ b/src/main/deploy/swerve/modules/backright.json @@ -5,12 +5,12 @@ }, "absoluteEncoderOffset": 5.537, "drive": { - "type": "sparkmax", + "type": "talonFX", "id": 11, "canbus": null }, "angle": { - "type": "sparkmax", + "type": "talonFX", "id": 12, "canbus": null }, diff --git a/src/main/java/frc/robot/Subsystems/Accumulateur.java b/src/main/java/frc/robot/Subsystems/Accumulateur.java index ad890d2..2eb7368 100644 --- a/src/main/java/frc/robot/Subsystems/Accumulateur.java +++ b/src/main/java/frc/robot/Subsystems/Accumulateur.java @@ -13,7 +13,7 @@ public class Accumulateur extends SubsystemBase { /** Creates a new Accumulateur. */ public Accumulateur() {dashboard.addBoolean("photocellacc", this::photocell).withSize(1, 1).withPosition(0, 1); - + dashboard.addBoolean("photocellacc2", this::photocell).withSize(1, 1).withPosition(0, 1); } ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard"); @@ -26,6 +26,7 @@ public class Accumulateur extends SubsystemBase { final WPI_TalonSRX accumulateur1 = new WPI_TalonSRX(0); final WPI_TalonSRX accumulateur2 = new WPI_TalonSRX(10); final DigitalInput photocell = new DigitalInput(94); + final DigitalInput photocell2 = new DigitalInput(93); public void encodeur(){ } public boolean photocell(){