diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 881999f..650fed4 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -74,21 +74,19 @@ public class RobotContainer { AllumeLED allumeLED = new AllumeLED(LED, accumulateur); Pistongrimpeur pistongrimpeur = new Pistongrimpeur(grimpeur, LED); public RobotContainer() { + dashboard.addCamera("limelight", "limelight","limelight.local:5800") .withSize(3,4) .withPosition(7,0); + dashboard.addCamera("USB Camera 0", "USB Camera 0","http://roborio-5618-frc.local:1181/?action=stream") .withSize(4, 4) .withPosition(3, 0); + NamedCommands.registerCommand("balayer",new Balayer(balayeuse, accumulateur)); NamedCommands.registerCommand("lancer", new LancerNote(lanceur, accumulateur)); NamedCommands.registerCommand("piston", new PistonFerme(grimpeur)); autoChooser = AutoBuilder.buildAutoChooser(); - - manette.a().whileTrue(new GuiderBas(guideur)); - dashboard.addCamera("USB Camera 0", "USB Camera 0","http://roborio-5618-frc.local:1181/?action=stream") - .withSize(4, 4) - .withPosition(3, 0); manette.a().whileTrue(new GuiderBas(guideur)); manette.b().whileTrue(new GuiderHaut(guideur)); @@ -110,7 +108,7 @@ public class RobotContainer { grimpeur.setDefaultCommand(new RunCommand(()->{ grimpeur.droit(MathUtil.applyDeadband(-manette.getLeftY(), 0.2)); grimpeur.gauche(MathUtil.applyDeadband(-manette.getRightY(),0.2 ));} - ,grimpeur)); + ,grimpeur)); LED.setDefaultCommand(allumeLED); diff --git a/src/main/java/frc/robot/command/LancerAmp.java b/src/main/java/frc/robot/command/LancerAmp.java index 30380ef..df9bf7e 100644 --- a/src/main/java/frc/robot/command/LancerAmp.java +++ b/src/main/java/frc/robot/command/LancerAmp.java @@ -25,7 +25,7 @@ public class LancerAmp extends Command { // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - double vitesse = 0.1; + double vitesse = 0.15; lancer.lanceramp(); if(lancer.vitesse(vitesse)>vitesse){ accumulateur.Accumuler(); diff --git a/src/main/java/frc/robot/subsystem/Drive.java b/src/main/java/frc/robot/subsystem/Drive.java index 54c88ab..d55cd6e 100644 --- a/src/main/java/frc/robot/subsystem/Drive.java +++ b/src/main/java/frc/robot/subsystem/Drive.java @@ -21,9 +21,9 @@ import swervelib.parser.SwerveParser; public class Drive extends SubsystemBase { /** Creates a new Drive. */ - public static final boolean kFrontLeftDriveMotorReversed = false; - public static final boolean kBackLeftDriveMotorReversed = false; - public static final boolean kFrontRightDriveMotorReversed = true; + public static final boolean kFrontLeftDriveMotorReversed = true; + public static final boolean kBackLeftDriveMotorReversed = true; + public static final boolean kFrontRightDriveMotorReversed = false; public static final boolean kBackRightDriveMotorReversed = true; SwerveDrive swerveDrive;