From 0b4c0e09ffe26951b76deb35fba71d0bf379ea1c Mon Sep 17 00:00:00 2001 From: Antoine PerreaultE Date: Tue, 7 Apr 2026 18:06:11 -0400 Subject: [PATCH 1/2] oui --- .../frc/robot/commands/ModeAuto/BougerDroiteAuto.java | 11 ----------- 1 file changed, 11 deletions(-) diff --git a/src/main/java/frc/robot/commands/ModeAuto/BougerDroiteAuto.java b/src/main/java/frc/robot/commands/ModeAuto/BougerDroiteAuto.java index 72952e7..2447477 100644 --- a/src/main/java/frc/robot/commands/ModeAuto/BougerDroiteAuto.java +++ b/src/main/java/frc/robot/commands/ModeAuto/BougerDroiteAuto.java @@ -46,23 +46,12 @@ public class BougerDroiteAuto extends Command { // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - if(alliance.get() == Alliance.Blue){ if(timer.get() < .75){ - System.out.println("8765"); drivetrain.setControl(drive.withVelocityY(-1.5)); } else{ drivetrain.setControl(drive.withVelocityY(0)); } - } - else{ - if(timer.get() < 0.75){ - drivetrain.setControl(drive.withVelocityY(1.5)); - } - else{ - drivetrain.setControl(drive.withVelocityY(0)); - } - } } // Called once the command ends or is interrupted. From 27ea9d96e3256ef46d44bada1df7a2432c66851e Mon Sep 17 00:00:00 2001 From: Antoine PerreaultE Date: Tue, 7 Apr 2026 19:51:41 -0400 Subject: [PATCH 2/2] grimpe --- src/main/java/frc/robot/subsystems/Grimpeur.java | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/Grimpeur.java b/src/main/java/frc/robot/subsystems/Grimpeur.java index 9ffd566..eb214bc 100644 --- a/src/main/java/frc/robot/subsystems/Grimpeur.java +++ b/src/main/java/frc/robot/subsystems/Grimpeur.java @@ -4,6 +4,8 @@ package frc.robot.subsystems; +import com.revrobotics.PersistMode; +import com.revrobotics.ResetMode; import com.revrobotics.spark.SparkMax; import com.revrobotics.spark.config.SparkMaxConfig; import com.revrobotics.spark.SparkLowLevel.MotorType; @@ -18,13 +20,15 @@ public class Grimpeur extends SubsystemBase { ShuffleboardTab teb = Shuffleboard.getTab("teb"); SparkMax grimpeur1 = new SparkMax(3,MotorType.kBrushless); SparkMax grimpeur2 = new SparkMax(12,MotorType.kBrushless); + SparkMaxConfig slaveConfig = new SparkMaxConfig(); DigitalInput limit = new DigitalInput(0); private GenericEntry EncodeurGrimpeur = teb.add("Position haut grimpeur", 100).getEntry(); public void Grimper(double vitesse){ + grimpeur1.configure(slaveConfig, ResetMode.kNoResetSafeParameters, PersistMode.kPersistParameters); + grimpeur2.configure(slaveConfig.follow(grimpeur1), ResetMode.kNoResetSafeParameters, PersistMode.kPersistParameters); grimpeur1.set(vitesse); - grimpeur2.set(vitesse); } public double Position(){ return grimpeur1.getEncoder().getPosition();