From fafc79523ea469d907bc9519db9cb53606676aed Mon Sep 17 00:00:00 2001 From: OlivierDubois Date: Sat, 17 Feb 2024 14:15:03 -0500 Subject: [PATCH] changement petit code vers gros --- src/main/java/frc/robot/Constants.java | 2 +- src/main/java/frc/robot/command/GrimpeurDroit.java | 6 ++---- .../java/frc/robot/command/GrimpeurGauche.java | 14 ++++++++------ src/main/java/frc/robot/command/PistonFerme.java | 6 ++++-- src/main/java/frc/robot/subsystem/Grimpeur.java | 2 +- 5 files changed, 16 insertions(+), 14 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 5735435..cdb9911 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -48,5 +48,5 @@ public class Constants { public static int photocellacc = 2; //piston - public static int pistondroiteouvre= 6; + public static int pistondroiteouvre= 7; } diff --git a/src/main/java/frc/robot/command/GrimpeurDroit.java b/src/main/java/frc/robot/command/GrimpeurDroit.java index 162d692..cb53ba4 100644 --- a/src/main/java/frc/robot/command/GrimpeurDroit.java +++ b/src/main/java/frc/robot/command/GrimpeurDroit.java @@ -24,16 +24,14 @@ public class GrimpeurDroit extends Command { @Override public void initialize() { grimpeur.resetencodeurd(); - grimpeur.pistonferme(); } // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { grimpeur.droit(doubleSupplier.getAsDouble()); - if(grimpeur.encoderd()>78){ - grimpeur.droit(0); - + if(grimpeur.encoderd()<73){ + grimpeur.droit(doubleSupplier.getAsDouble()); } else if(grimpeur.getpitch()<-15){ grimpeur.droit(-doubleSupplier.getAsDouble()); diff --git a/src/main/java/frc/robot/command/GrimpeurGauche.java b/src/main/java/frc/robot/command/GrimpeurGauche.java index ea9d860..df8891e 100644 --- a/src/main/java/frc/robot/command/GrimpeurGauche.java +++ b/src/main/java/frc/robot/command/GrimpeurGauche.java @@ -23,17 +23,17 @@ public class GrimpeurGauche extends Command { // Called when the command is initially scheduled. @Override public void initialize() { - grimpeur.resetencodeurd(); grimpeur.resetencodeurg(); + } // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { grimpeur.gauche(doubleSupplier.getAsDouble()); - if(grimpeur.encoderg()>73){ - grimpeur.gauche(0); - } + if(grimpeur.encoderg()<78){ + grimpeur.gauche(doubleSupplier.getAsDouble()); + } else if(grimpeur.getpitch()<-15){ grimpeur.gauche(doubleSupplier.getAsDouble()); } @@ -43,10 +43,12 @@ public class GrimpeurGauche extends Command { else{ grimpeur.gauche(0); } - if(grimpeur.encoderd()>0){ + if(grimpeur.encoderg()<0){ + grimpeur.gauche(doubleSupplier.getAsDouble()); + } + else{ grimpeur.resetencodeurg(); grimpeur.gauche(0); - } } diff --git a/src/main/java/frc/robot/command/PistonFerme.java b/src/main/java/frc/robot/command/PistonFerme.java index b4ef3fd..c072790 100644 --- a/src/main/java/frc/robot/command/PistonFerme.java +++ b/src/main/java/frc/robot/command/PistonFerme.java @@ -19,7 +19,7 @@ public class PistonFerme extends Command { // Called when the command is initially scheduled. @Override public void initialize() { - grimpeur.pistonferme(); + grimpeur.pistonouvre(); } // Called every time the scheduler runs while the command is scheduled. @@ -28,7 +28,9 @@ public class PistonFerme extends Command { // Called once the command ends or is interrupted. @Override - public void end(boolean interrupted) {} + public void end(boolean interrupted) { + grimpeur.pistonferme(); + } // Returns true when the command should end. @Override diff --git a/src/main/java/frc/robot/subsystem/Grimpeur.java b/src/main/java/frc/robot/subsystem/Grimpeur.java index 045a1be..e16af68 100644 --- a/src/main/java/frc/robot/subsystem/Grimpeur.java +++ b/src/main/java/frc/robot/subsystem/Grimpeur.java @@ -28,7 +28,7 @@ public class Grimpeur extends SubsystemBase { final CANSparkMax grimpeurd = new CANSparkMax(Constants.grimpeurd,MotorType.kBrushless); final CANSparkMax grimpeurg = new CANSparkMax(Constants.grimpeurg,MotorType.kBrushless); // limit switch - final Solenoid pistondroite= new Solenoid(PneumaticsModuleType.CTREPCM, Constants.pistondroiteouvre); + final Solenoid pistondroite= new Solenoid(PneumaticsModuleType.REVPH, Constants.pistondroiteouvre); //fonction public Grimpeur() { pistonouvre();