From 9f64f15ae4b08a413851217b153f9b1357dac479 Mon Sep 17 00:00:00 2001 From: Samuel <2540638@etudiant.cegepvicto.com> Date: Mon, 27 Oct 2025 17:45:07 -0400 Subject: [PATCH] pid pour L3 --- src/main/java/frc/robot/commands/Elevateur/L3.java | 2 +- src/main/java/frc/robot/subsystems/Elevateur.java | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/commands/Elevateur/L3.java b/src/main/java/frc/robot/commands/Elevateur/L3.java index 8011b68..e3880db 100644 --- a/src/main/java/frc/robot/commands/Elevateur/L3.java +++ b/src/main/java/frc/robot/commands/Elevateur/L3.java @@ -33,7 +33,7 @@ public class L3 extends Command { // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - output = pidController.calculate(elevateur.position(),20); + output = pidController.calculate(elevateur.position(),-3); elevateur.vitesse(output); // if(elevateur.position()<=elevateur.encodeurelevateurL3bas() && elevateur.position()>=elevateur.encodeurelevateurL3haut()){ // elevateur.vitesse(0); diff --git a/src/main/java/frc/robot/subsystems/Elevateur.java b/src/main/java/frc/robot/subsystems/Elevateur.java index 1ef7681..de500a4 100644 --- a/src/main/java/frc/robot/subsystems/Elevateur.java +++ b/src/main/java/frc/robot/subsystems/Elevateur.java @@ -8,6 +8,8 @@ import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; + import com.revrobotics.spark.SparkMax; import com.revrobotics.spark.SparkLowLevel.MotorType; public class Elevateur extends SubsystemBase { @@ -38,7 +40,6 @@ public class Elevateur extends SubsystemBase { } final SparkMax monte = new SparkMax(22, MotorType.kBrushless); final DigitalInput limit2 = new DigitalInput(0); - public double position(){ return monte.getEncoder().getPosition(); } @@ -90,7 +91,6 @@ public class Elevateur extends SubsystemBase { return distanceDeploiePince.getDouble(0.2); } - @Override public void periodic() { // This method will be called once per scheduler run