pid d`édouard

This commit is contained in:
EdwardFaucher
2025-10-29 18:34:30 -04:00
parent 837435643b
commit 3715451972
8 changed files with 84 additions and 45 deletions

View File

@@ -3,6 +3,7 @@
// the WPILib BSD license file in the root directory of this project.
package frc.robot.commands.Elevateur;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Elevateur;
import frc.robot.subsystems.Pince;
@@ -11,6 +12,8 @@ import frc.robot.subsystems.Pince;
public class L2 extends Command {
private Elevateur elevateur;
private Pince pince;
private PIDController pidController;
private double output;
/** Creates a new L2. */
public L2(Elevateur elevateur,Pince pince) {
this.elevateur = elevateur;
@@ -21,20 +24,24 @@ public class L2 extends Command {
// Called when the command is initially scheduled.
@Override
public void initialize() {}
public void initialize() {
pidController = new PIDController(0.025, 0.00125,0.001, 0.01);
}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if(pince.encodeurpivot()>=15 && pince.encodeurpivot()<=16.5){
pince.pivote(0);
}
else if(pince.encodeurpivot()>=15){
pince.pivote(-0.2);
}
else{
pince.pivote(0.1);
}
output = pidController.calculate(pince.encodeurpivot(),15);
pince.pivote(output);
// if(pince.encodeurpivot()>=15 && pince.encodeurpivot()<=16.5){
// pince.pivote(0);
// }
// else if(pince.encodeurpivot()>=15){
// pince.pivote(-0.2);
// }
// else{
// pince.pivote(0.1);
// }
}

View File

@@ -13,8 +13,10 @@ import frc.robot.subsystems.Pince;
public class L3 extends Command {
private Elevateur elevateur;
private Pince pince;
private PIDController pidController;
private PIDController pidController1;
private PIDController pidController2;
private double output;
private double output2;
/** Creates a new L2. */
public L3(Elevateur elevateur,Pince pince) {
this.elevateur = elevateur;
@@ -26,15 +28,19 @@ public class L3 extends Command {
// Called when the command is initially scheduled.
@Override
public void initialize() {
pidController = new PIDController(0.03, 0.001, 0.001);
pidController.reset();
pidController1 = new PIDController(0.3, 0.04,0);
pidController2 = new PIDController(0.025, 0.00125,0.001, 0.01);
pidController1.reset();
pidController2.reset();
}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
output = pidController.calculate(elevateur.position(),20);
output = pidController1.calculate(elevateur.position(),-3);
output2 = pidController2.calculate(pince.encodeurpivot(),20);
elevateur.vitesse(output);
pince.pivote(output2);
// if(elevateur.position()<=elevateur.encodeurelevateurL3bas() && elevateur.position()>=elevateur.encodeurelevateurL3haut()){
// elevateur.vitesse(0);
// pince.pivote(-0.15);

View File

@@ -4,6 +4,7 @@
package frc.robot.commands.Elevateur;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Elevateur;
import frc.robot.subsystems.Pince;
@@ -12,6 +13,10 @@ import frc.robot.subsystems.Pince;
public class L4 extends Command {
private Elevateur elevateur;
private Pince pince;
private PIDController pidController;
private PIDController pidController1;
private double output;
private double output1;
/** Creates a new L2. */
public L4(Elevateur elevateur,Pince pince) {
this.elevateur = elevateur;
@@ -22,30 +27,39 @@ public class L4 extends Command {
// Called when the command is initially scheduled.
@Override
public void initialize() {}
public void initialize() {
pidController = new PIDController(0.3, 0.04,0);
pidController1 = new PIDController(0.025, 0.00125,0.001, 0.01);
pidController.reset();
pidController1.reset();
}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if(elevateur.position()<=elevateur.encodeurelevateurL4bas() && elevateur.position()>=elevateur.encodeurelevateurL4haut()){
elevateur.vitesse(0);
pince.pivote(-0.15);
if(pince.encodeurpivot()>=20 && pince.encodeurpivot()<=21){
pince.pivote(0);
}
else if(pince.encodeurpivot()>=20){
pince.pivote(-0.15);
}
else{
pince.pivote(0.15);
}
}
else if(elevateur.position()>=elevateur.encodeurelevateurL4bas()){
elevateur.vitesse(-0.7);
}
else{
elevateur.vitesse(.25);
}
output = pidController.calculate(elevateur.position(),-6.3);
elevateur.vitesse(output);
output1 = pidController1.calculate(pince.encodeurpivot(),20);
pince.pivote(output1);
// if(elevateur.position()<=elevateur.encodeurelevateurL4bas() && elevateur.position()>=elevateur.encodeurelevateurL4haut()){
// elevateur.vitesse(0);
// pince.pivote(-0.15);
// if(pince.encodeurpivot()>=20 && pince.encodeurpivot()<=21){
// pince.pivote(0);
// }
// else if(pince.encodeurpivot()>=20){
// pince.pivote(-0.15);
// }
// else{
// pince.pivote(0.15);
// }
// }
// else if(elevateur.position()>=elevateur.encodeurelevateurL4bas()){
// elevateur.vitesse(-0.7);
// }
// else{
// elevateur.vitesse(.25);
// }
}
// Called once the command ends or is interrupted.