This commit is contained in:
		| @@ -13,7 +13,8 @@ import edu.wpi.first.wpilibj2.command.RunCommand; | ||||
| // Manette | ||||
| import edu.wpi.first.wpilibj2.command.button.CommandJoystick; | ||||
| import edu.wpi.first.wpilibj2.command.button.CommandXboxController; | ||||
|  | ||||
| import frc.robot.command.GuiderBas; | ||||
| import frc.robot.command.GuiderHaut; | ||||
| // Subsystem | ||||
| import frc.robot.subsystem.Accumulateur; | ||||
| import frc.robot.subsystem.Balayeuse; | ||||
| @@ -31,14 +32,16 @@ public class RobotContainer { | ||||
|   Grimpeur grimpeur = new Grimpeur(); | ||||
|   Guideur guideur = new Guideur(); | ||||
|   Lanceur lanceur = new Lanceur(); | ||||
|  | ||||
|   GuiderHaut guiderHaut = new GuiderHaut(guideur); | ||||
|   GuiderBas guiderBas = new GuiderBas(guideur); | ||||
|    CommandJoystick joystick = new CommandJoystick(0); | ||||
|    CommandXboxController manette = new CommandXboxController(1); | ||||
|    | ||||
|   public RobotContainer() { | ||||
|  | ||||
|     CameraServer.startAutomaticCapture(); | ||||
|  | ||||
|     manette.a().onTrue(guiderBas); | ||||
|     manette.b().onTrue(guiderHaut); | ||||
|     configureBindings(); | ||||
|      drive.setDefaultCommand(new RunCommand(()->{ | ||||
|      drive.drive(-MathUtil.applyDeadband(joystick.getY(),0.2), MathUtil.applyDeadband(-joystick.getX(),0.2), MathUtil.applyDeadband(-joystick.getZ(), 0.2)); | ||||
|   | ||||
| @@ -1,51 +0,0 @@ | ||||
| // Copyright (c) FIRST and other WPILib contributors. | ||||
| // Open Source Software; you can modify and/or share it under the terms of | ||||
| // the WPILib BSD license file in the root directory of this project. | ||||
|  | ||||
| package frc.robot.command; | ||||
|  | ||||
| import edu.wpi.first.wpilibj2.command.Command; | ||||
| import frc.robot.subsystem.Grimpeur; | ||||
|  | ||||
| public class GrimpeurBas extends Command { | ||||
|   private Grimpeur grimpeur; | ||||
|   /** Creates a new GrimpeurBas. */ | ||||
|   public GrimpeurBas(Grimpeur grimpeur) { | ||||
|     this.grimpeur = grimpeur; | ||||
|     addRequirements(grimpeur); | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|   } | ||||
|  | ||||
|   // 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() { | ||||
|     if(grimpeur.droite()){ | ||||
|       grimpeur.resetencodeurd(); | ||||
|       grimpeur.gauche(0); | ||||
|     } | ||||
|     if(grimpeur.gauche()){ | ||||
|       grimpeur.resetencodeurg(); | ||||
|       grimpeur.gauche(0); | ||||
|     } | ||||
|   } | ||||
|  | ||||
|   // Called once the command ends or is interrupted. | ||||
|   @Override | ||||
|   public void end(boolean interrupted) { | ||||
|     grimpeur.droit(0); | ||||
|     grimpeur.gauche(0); | ||||
|   } | ||||
|  | ||||
|   // Returns true when the command should end. | ||||
|   @Override | ||||
|   public boolean isFinished() { | ||||
|     return false; | ||||
|   } | ||||
| } | ||||
| @@ -10,7 +10,7 @@ import frc.robot.subsystem.Guideur; | ||||
| public class GuiderHaut extends Command { | ||||
|   private Guideur guideur; | ||||
|   /** Creates a new GuiderHaut. */ | ||||
|   public GuiderHaut() { | ||||
|   public GuiderHaut(Guideur guideur) { | ||||
|     this.guideur = guideur; | ||||
|     addRequirements(guideur); | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|   | ||||
| @@ -16,7 +16,7 @@ public class Guideur extends SubsystemBase { | ||||
|    | ||||
|     final WPI_TalonSRX guideur = new WPI_TalonSRX(Constants.guideur); | ||||
|     final DigitalInput guideurhaut = new DigitalInput(Constants.guideurhaut); | ||||
|     final DigitalInput guideurbas = new DigitalInput(Constants.guideurhaut); | ||||
|     final DigitalInput guideurbas = new DigitalInput(Constants.guideurbas); | ||||
|  | ||||
|       public void guider(double vitesse){ | ||||
|         guideur.set(vitesse); | ||||
|   | ||||
		Reference in New Issue
	
	Block a user