Merge branch 'main' of https://git.demerso.net/pls5618/2024/robot
This commit is contained in:
		| @@ -48,5 +48,5 @@ public class Constants { | |||||||
|     public static int photocellacc = 2; |     public static int photocellacc = 2; | ||||||
|  |  | ||||||
|     //piston |     //piston | ||||||
|     public static int pistondroiteouvre= 6; |     public static int pistondroiteouvre= 7; | ||||||
| } | } | ||||||
|   | |||||||
| @@ -81,6 +81,7 @@ public class RobotContainer { | |||||||
|     manette.a().whileTrue(new GuiderBas(guideur)); |     manette.a().whileTrue(new GuiderBas(guideur)); | ||||||
|     manette.b().whileTrue(new GuiderHaut(guideur)); |     manette.b().whileTrue(new GuiderHaut(guideur)); | ||||||
|     manette.x().whileTrue(new PistonFerme(grimpeur)); |     manette.x().whileTrue(new PistonFerme(grimpeur)); | ||||||
|  |    | ||||||
|     joystick.button(3).whileTrue(balayer); |     joystick.button(3).whileTrue(balayer); | ||||||
|     joystick.button(1).whileTrue(new LancerNote(lanceur, accumulateur)); |     joystick.button(1).whileTrue(new LancerNote(lanceur, accumulateur)); | ||||||
|     joystick.button(5).whileTrue(new LancerAmp(lanceur, accumulateur)); |     joystick.button(5).whileTrue(new LancerAmp(lanceur, accumulateur)); | ||||||
| @@ -95,8 +96,8 @@ public class RobotContainer { | |||||||
|  |  | ||||||
|     // grimpeur manuel |     // grimpeur manuel | ||||||
|     grimpeur.setDefaultCommand(new RunCommand(()->{ |     grimpeur.setDefaultCommand(new RunCommand(()->{ | ||||||
|       grimpeur.droit(manette.getLeftY()); |     grimpeur.droit(MathUtil.applyDeadband(manette.getLeftY(), 0.2)); | ||||||
|     grimpeur.gauche(manette.getRightY());} |     grimpeur.gauche(MathUtil.applyDeadband(manette.getRightY(),0.2 ));} | ||||||
|       ,grimpeur)); |       ,grimpeur)); | ||||||
|  |  | ||||||
|       LED.setDefaultCommand(allumeLED); |       LED.setDefaultCommand(allumeLED); | ||||||
|   | |||||||
| @@ -24,16 +24,14 @@ public class GrimpeurDroit extends Command { | |||||||
|   @Override |   @Override | ||||||
|   public void initialize() { |   public void initialize() { | ||||||
|     grimpeur.resetencodeurd(); |     grimpeur.resetencodeurd(); | ||||||
|     grimpeur.pistonferme(); |  | ||||||
|   } |   } | ||||||
|  |  | ||||||
|   // Called every time the scheduler runs while the command is scheduled. |   // Called every time the scheduler runs while the command is scheduled. | ||||||
|   @Override |   @Override | ||||||
|   public void execute() { |   public void execute() { | ||||||
|     grimpeur.droit(doubleSupplier.getAsDouble()); |     grimpeur.droit(doubleSupplier.getAsDouble()); | ||||||
|   if(grimpeur.encoderd()>78){ |   if(grimpeur.encoderd()<73){ | ||||||
|     grimpeur.droit(0); |     grimpeur.droit(doubleSupplier.getAsDouble()); | ||||||
|      |  | ||||||
|   } |   } | ||||||
|   else if(grimpeur.getpitch()<-15){ |   else if(grimpeur.getpitch()<-15){ | ||||||
|     grimpeur.droit(-doubleSupplier.getAsDouble()); |     grimpeur.droit(-doubleSupplier.getAsDouble()); | ||||||
|   | |||||||
| @@ -23,17 +23,17 @@ public class GrimpeurGauche extends Command { | |||||||
|   // Called when the command is initially scheduled. |   // Called when the command is initially scheduled. | ||||||
|   @Override |   @Override | ||||||
|   public void initialize() { |   public void initialize() { | ||||||
|     grimpeur.resetencodeurd(); |  | ||||||
|     grimpeur.resetencodeurg(); |     grimpeur.resetencodeurg(); | ||||||
|  |  | ||||||
|   } |   } | ||||||
|  |  | ||||||
|   // Called every time the scheduler runs while the command is scheduled. |   // Called every time the scheduler runs while the command is scheduled. | ||||||
|   @Override |   @Override | ||||||
|   public void execute() { |   public void execute() { | ||||||
|     grimpeur.gauche(doubleSupplier.getAsDouble()); |     grimpeur.gauche(doubleSupplier.getAsDouble()); | ||||||
|     if(grimpeur.encoderg()>73){ |     if(grimpeur.encoderg()<78){ | ||||||
|       grimpeur.gauche(0); |       grimpeur.gauche(doubleSupplier.getAsDouble()); | ||||||
|     } |      } | ||||||
|     else if(grimpeur.getpitch()<-15){ |     else if(grimpeur.getpitch()<-15){ | ||||||
|       grimpeur.gauche(doubleSupplier.getAsDouble()); |       grimpeur.gauche(doubleSupplier.getAsDouble()); | ||||||
|     } |     } | ||||||
| @@ -43,10 +43,12 @@ public class GrimpeurGauche extends Command { | |||||||
|     else{ |     else{ | ||||||
|       grimpeur.gauche(0); |       grimpeur.gauche(0); | ||||||
|     } |     } | ||||||
|     if(grimpeur.encoderd()>0){ |     if(grimpeur.encoderg()<0){ | ||||||
|  |       grimpeur.gauche(doubleSupplier.getAsDouble()); | ||||||
|  |     } | ||||||
|  |     else{ | ||||||
|       grimpeur.resetencodeurg(); |       grimpeur.resetencodeurg(); | ||||||
|       grimpeur.gauche(0); |       grimpeur.gauche(0); | ||||||
|        |  | ||||||
|     } |     } | ||||||
|   } |   } | ||||||
|  |  | ||||||
|   | |||||||
| @@ -19,7 +19,7 @@ public class PistonFerme extends Command { | |||||||
|   // Called when the command is initially scheduled. |   // Called when the command is initially scheduled. | ||||||
|   @Override |   @Override | ||||||
|   public void initialize() { |   public void initialize() { | ||||||
|     grimpeur.pistonferme(); |     grimpeur.pistonouvre(); | ||||||
|   } |   } | ||||||
|  |  | ||||||
|   // Called every time the scheduler runs while the command is scheduled. |   // 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. |   // Called once the command ends or is interrupted. | ||||||
|   @Override |   @Override | ||||||
|   public void end(boolean interrupted) {} |   public void end(boolean interrupted) { | ||||||
|  |     grimpeur.pistonferme(); | ||||||
|  |   } | ||||||
|  |  | ||||||
|   // Returns true when the command should end. |   // Returns true when the command should end. | ||||||
|   @Override |   @Override | ||||||
|   | |||||||
| @@ -28,7 +28,7 @@ public class Grimpeur extends SubsystemBase { | |||||||
|   final CANSparkMax grimpeurd = new CANSparkMax(Constants.grimpeurd,MotorType.kBrushless); |   final CANSparkMax grimpeurd = new CANSparkMax(Constants.grimpeurd,MotorType.kBrushless); | ||||||
|   final CANSparkMax grimpeurg = new CANSparkMax(Constants.grimpeurg,MotorType.kBrushless);  |   final CANSparkMax grimpeurg = new CANSparkMax(Constants.grimpeurg,MotorType.kBrushless);  | ||||||
|   // limit switch |   // limit switch | ||||||
|   final Solenoid pistondroite= new Solenoid(PneumaticsModuleType.CTREPCM, Constants.pistondroiteouvre); |   final Solenoid pistondroite= new Solenoid(PneumaticsModuleType.REVPH, Constants.pistondroiteouvre); | ||||||
|   //fonction |   //fonction | ||||||
|   public Grimpeur() { |   public Grimpeur() { | ||||||
|     pistonouvre(); |     pistonouvre(); | ||||||
|   | |||||||
		Reference in New Issue
	
	Block a user