From b9cac9ee360b88f7ce7ac495ff140d063a2ed189 Mon Sep 17 00:00:00 2001 From: Samuel <2540638@etudiant.cegepvicto.com> Date: Tue, 24 Feb 2026 18:55:48 -0500 Subject: [PATCH] mode oppose fait --- src/main/java/frc/robot/RobotContainer.java | 2 ++ src/main/java/frc/robot/commands/Lancer.java | 3 +- .../{LancerOposer.java => ModeOposer.java} | 29 ++++--------------- .../java/frc/robot/subsystems/Balayeuse.java | 1 - src/main/java/frc/robot/subsystems/Led.java | 2 -- 5 files changed, 10 insertions(+), 27 deletions(-) rename src/main/java/frc/robot/commands/{LancerOposer.java => ModeOposer.java} (62%) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 3dc5b34..4ab327e 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -12,6 +12,7 @@ import frc.robot.commands.Aspirer; import frc.robot.commands.DescendreBalyeuse; import frc.robot.commands.DescendreGrimpeur; import frc.robot.commands.Lancer; +import frc.robot.commands.ModeOposer; import frc.robot.commands.MonterBalyeuse; import frc.robot.commands.MonterGrimpeur; import frc.robot.subsystems.Balayeuse; @@ -34,6 +35,7 @@ public class RobotContainer { private void configureBindings() { manette.a().whileTrue(new Lancer(lanceur,limeLight3,balayeuse,led)); + manette.y().whileTrue(new ModeOposer(lanceur, balayeuse)); manette.rightTrigger().whileTrue(new MonterGrimpeur(grimpeur)); manette.leftTrigger().whileTrue(new DescendreGrimpeur(grimpeur)); manette.rightBumper().whileTrue(new MonterBalyeuse(balayeuse)); diff --git a/src/main/java/frc/robot/commands/Lancer.java b/src/main/java/frc/robot/commands/Lancer.java index 1c32190..d3816b0 100644 --- a/src/main/java/frc/robot/commands/Lancer.java +++ b/src/main/java/frc/robot/commands/Lancer.java @@ -29,7 +29,7 @@ public class Lancer extends Command { this.led = led; this.timer = new Timer(); this.limeLight3G = new Limelight3G(); - addRequirements(lanceur); + addRequirements(lanceur, balayeuse, led, limeLight3G); this.temp = 0; // Use addRequirements() here to declare subsystem dependencies. } @@ -62,6 +62,7 @@ public class Lancer extends Command { if(moyenneAmp > 30 && nbFois > 10){ timer.reset(); balayeuse.Balayer(0.5); + led.Jaune2(); } else{ double vitesse = (100-limeLight3G.getTA())/lanceur.Vitesse(); diff --git a/src/main/java/frc/robot/commands/LancerOposer.java b/src/main/java/frc/robot/commands/ModeOposer.java similarity index 62% rename from src/main/java/frc/robot/commands/LancerOposer.java rename to src/main/java/frc/robot/commands/ModeOposer.java index 4c129c6..068afc8 100644 --- a/src/main/java/frc/robot/commands/LancerOposer.java +++ b/src/main/java/frc/robot/commands/ModeOposer.java @@ -4,43 +4,24 @@ package frc.robot.commands; -import edu.wpi.first.math.controller.PIDController; -import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj2.command.Command; import frc.robot.subsystems.Balayeuse; import frc.robot.subsystems.Lanceur; -import frc.robot.subsystems.Led; -import frc.robot.subsystems.LimeLight3; -import frc.robot.subsystems.Limelight3G; - /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ -public class LancerOposer extends Command { +public class ModeOposer extends Command { private Lanceur lanceur; - private PIDController pidController; - private Limelight3G limeLight3G; - private Timer timer; private Balayeuse balayeuse; - private Led led; - private double temp; /** Creates a new Lancer. */ - public LancerOposer(Lanceur lanceur, LimeLight3 limeLight3, Balayeuse balayeuse,Led led) { + public ModeOposer(Lanceur lanceur, Balayeuse balayeuse) { this.lanceur = lanceur; this.balayeuse = balayeuse; - this.led = led; - this.timer = new Timer(); - this.limeLight3G = new Limelight3G(); - addRequirements(lanceur); - this.temp = 0; + addRequirements(lanceur ,balayeuse); // Use addRequirements() here to declare subsystem dependencies. } // Called when the command is initially scheduled. @Override - public void initialize() { - pidController = new PIDController(0, 0,0, 0); - timer.reset(); - timer.start(); - temp = lanceur.Amp(); + public void initialize() { } // Called every time the scheduler runs while the command is scheduled. @@ -48,6 +29,7 @@ public class LancerOposer extends Command { public void execute() { lanceur.Lancer(-0.2); lanceur.Demeler(-0.2); + balayeuse.Balayer(-0.2); } // Called once the command ends or is interrupted. @@ -55,6 +37,7 @@ public class LancerOposer extends Command { public void end(boolean interrupted) { lanceur.Demeler(0); lanceur.Lancer(0); + balayeuse.Balayer(0); } // Returns true when the command should end. diff --git a/src/main/java/frc/robot/subsystems/Balayeuse.java b/src/main/java/frc/robot/subsystems/Balayeuse.java index 141dbe2..d0ffb4e 100644 --- a/src/main/java/frc/robot/subsystems/Balayeuse.java +++ b/src/main/java/frc/robot/subsystems/Balayeuse.java @@ -9,7 +9,6 @@ import com.revrobotics.spark.SparkMax; import com.revrobotics.spark.SparkLowLevel.MotorType; import edu.wpi.first.networktables.GenericEntry; -import edu.wpi.first.units.measure.Time; import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; diff --git a/src/main/java/frc/robot/subsystems/Led.java b/src/main/java/frc/robot/subsystems/Led.java index 533a8ae..4885a13 100644 --- a/src/main/java/frc/robot/subsystems/Led.java +++ b/src/main/java/frc/robot/subsystems/Led.java @@ -4,8 +4,6 @@ package frc.robot.subsystems; -import java.util.Optional; - import com.ctre.phoenix.led.CANdle; import com.ctre.phoenix.led.RainbowAnimation;