diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 11a419e..6ba36d8 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -88,14 +88,9 @@ public class RobotContainer { Cube cube = new Cube(limelight, basePilotable, () -> manette1.getLeftY()); Apriltag aprilTag = new Apriltag(limelight, basePilotable, () -> manette1.getLeftY()); Tape tape = new Tape(limelight, basePilotable, () -> manette1.getLeftY()); -<<<<<<< HEAD PivotManuel pivotManuel = new PivotManuel(pivot, manette1::getRightY); BrasManuel brasManuel = new BrasManuel(brasTelescopique, manette1::getRightX); -======= - PivotManuel pivotManuel = new PivotManuel(pivot, manette1::getLeftY); - BrasManuel brasManuel = new BrasManuel(brasTelescopique, manette1::getLeftX); ActiverLimeLight activerLimeLight = new ActiverLimeLight(limelight); ->>>>>>> 1da49837db76e3ae31f03d0e1593aec704cc02df public RobotContainer() { chooser.addOption(enhaut, enhaut); @@ -123,12 +118,8 @@ public class RobotContainer { manette1.povDown().whileTrue(creerCommandBras(9, -14)); manette1.povRight().whileTrue(creerCommandBras(44, -17)); manette1.povLeft().whileTrue(creerCommandBras(0, 0)); -<<<<<<< HEAD - // manette 2 -======= manette1.y().whileTrue(activerLimeLight); //manette 2 ->>>>>>> 1da49837db76e3ae31f03d0e1593aec704cc02df manette2.povDown().whileTrue(creerCommandBras(9, -18)); manette2.povUp().whileTrue(creerCommandBras(44, 0)); manette2.rightBumper().whileTrue(cube); diff --git a/src/main/java/frc/robot/commands/bras/PivoteBrasBas.java b/src/main/java/frc/robot/commands/bras/PivoteBrasBas.java index a6015d7..8f029b3 100644 --- a/src/main/java/frc/robot/commands/bras/PivoteBrasBas.java +++ b/src/main/java/frc/robot/commands/bras/PivoteBrasBas.java @@ -31,21 +31,21 @@ public class PivoteBrasBas extends CommandBase { // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - if(brasTelescopique.distance()>-13.5){ + if(brasTelescopique.distance()>-8.5){ brasTelescopique.AvanceRecule(-0.2); brasTelescopique.fermer(); } - else if(brasTelescopique.distance()<-15.5) { + else if(brasTelescopique.distance()<-9.5) { brasTelescopique.AvanceRecule(0.2); } else { brasTelescopique.AvanceRecule(0); brasTelescopique.ouvrir(); } - if (pivot.distance()<8.5){ + if (pivot.distance()<12.5){ pivot.monteDescendre(0.4); } - else if(pivot.distance()>10.5) { + else if(pivot.distance()>13.5) { pivot.monteDescendre(-0.4); } else{ diff --git a/src/main/java/frc/robot/commands/bras/PivoteBrasMilieux.java b/src/main/java/frc/robot/commands/bras/PivoteBrasMilieux.java index 764050b..4494a33 100644 --- a/src/main/java/frc/robot/commands/bras/PivoteBrasMilieux.java +++ b/src/main/java/frc/robot/commands/bras/PivoteBrasMilieux.java @@ -29,11 +29,11 @@ public class PivoteBrasMilieux extends CommandBase { // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - if(brasTelescopique.distance()>-16.5){ + if(brasTelescopique.distance()>-12.5){ brasTelescopique.AvanceRecule(-0.15); brasTelescopique.fermer(); } - else if(brasTelescopique.distance()<-17.5) { + else if(brasTelescopique.distance()<-13.5) { brasTelescopique.AvanceRecule(0.15); } else {