Merge branch 'main' of https://demerso.net/pls5618/2023/robot
This commit is contained in:
		| @@ -6,6 +6,7 @@ package frc.robot; | |||||||
|  |  | ||||||
| import java.util.Map; | import java.util.Map; | ||||||
|  |  | ||||||
|  |  | ||||||
| import edu.wpi.first.cameraserver.CameraServer; | import edu.wpi.first.cameraserver.CameraServer; | ||||||
| import edu.wpi.first.networktables.GenericEntry; | import edu.wpi.first.networktables.GenericEntry; | ||||||
| import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts; | import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts; | ||||||
| @@ -64,7 +65,6 @@ public class RobotContainer { | |||||||
|   GenericEntry reculerdistances = layoutauto.addPersistent("reculerdistancesortir", -66).getEntry(); |   GenericEntry reculerdistances = layoutauto.addPersistent("reculerdistancesortir", -66).getEntry(); | ||||||
|   GenericEntry reculerdistanceb = layoutauto.addPersistent("reculerdistancebalance", -31).getEntry(); |   GenericEntry reculerdistanceb = layoutauto.addPersistent("reculerdistancebalance", -31).getEntry(); | ||||||
|   GenericEntry avancerdistance = layoutauto.addPersistent("avancer", 35).getEntry(); |   GenericEntry avancerdistance = layoutauto.addPersistent("avancer", 35).getEntry(); | ||||||
|    |  | ||||||
|   // subsystems |   // subsystems | ||||||
|   BasePilotable basePilotable = new BasePilotable(); |   BasePilotable basePilotable = new BasePilotable(); | ||||||
|   Gratte gratte = new Gratte(); |   Gratte gratte = new Gratte(); | ||||||
| @@ -114,13 +114,13 @@ public class RobotContainer { | |||||||
|     manette2.b().onTrue(brakeFerme); |     manette2.b().onTrue(brakeFerme); | ||||||
|     manette1.leftBumper().whileTrue(aprilTag); |     manette1.leftBumper().whileTrue(aprilTag); | ||||||
|     manette1.rightBumper().whileTrue(tape); |     manette1.rightBumper().whileTrue(tape); | ||||||
|     manette1.povUp().whileTrue(creerCommandBras(51, -37)); |     manette1.povUp().whileTrue(creerCommandBras(51, -40)); | ||||||
|     manette1.povDown().whileTrue(creerCommandBras(12, -9)); |     manette1.povDown().whileTrue(creerCommandBras(9, -14)); | ||||||
|     manette1.povRight().whileTrue(creerCommandBras(45, -13)); |     manette1.povRight().whileTrue(creerCommandBras(44, -17)); | ||||||
|     manette1.povLeft().whileTrue(creerCommandBras(0, 0)); |     manette1.povLeft().whileTrue(creerCommandBras(0, 0)); | ||||||
|     manette1.y().whileTrue(activerLimeLight); |     manette1.y().whileTrue(activerLimeLight); | ||||||
|     //manette 2 |     //manette 2 | ||||||
|     manette2.povDown().whileTrue(creerCommandBras(5, -12)); |     manette2.povDown().whileTrue(creerCommandBras(9, -18)); | ||||||
|     manette2.povUp().whileTrue(creerCommandBras(44, 0)); |     manette2.povUp().whileTrue(creerCommandBras(44, 0)); | ||||||
|     manette2.rightBumper().whileTrue(cube); |     manette2.rightBumper().whileTrue(cube); | ||||||
|     manette2.leftBumper().whileTrue(cone); |     manette2.leftBumper().whileTrue(cone); | ||||||
| @@ -128,6 +128,7 @@ public class RobotContainer { | |||||||
|     manette2.start().onTrue(new InstantCommand(basePilotable::resetGyro)); |     manette2.start().onTrue(new InstantCommand(basePilotable::resetGyro)); | ||||||
|     manette1.b().whileTrue(gratteMonte); |     manette1.b().whileTrue(gratteMonte); | ||||||
|     manette1.x().whileTrue(gratteBaisser); |     manette1.x().whileTrue(gratteBaisser); | ||||||
|  |  | ||||||
|   } |   } | ||||||
|  |  | ||||||
|   private Command creerCommandBras(double distancePivot, double distanceBras) { |   private Command creerCommandBras(double distancePivot, double distanceBras) { | ||||||
| @@ -138,15 +139,15 @@ public class RobotContainer { | |||||||
|   } |   } | ||||||
|  |  | ||||||
|   public Command getAutonomousCommand() { |   public Command getAutonomousCommand() { | ||||||
|  |     chooser.getSelected(); | ||||||
|  |     autobalance.getBoolean(true); | ||||||
|     return Commands.deadline( |     return Commands.deadline( | ||||||
|         Commands.waitSeconds(14), |         Commands.waitSeconds(14.6), | ||||||
|         new SequentialCommandGroup( |         new SequentialCommandGroup( | ||||||
|           new BrakeFerme(basePilotable), |  | ||||||
|             Commands.select(Map.ofEntries( |             Commands.select(Map.ofEntries( | ||||||
|                 Map.entry(enhaut, creerCommandBras(51, -40)), |                 Map.entry(enhaut, creerCommandBras(51, -40)), | ||||||
|                 Map.entry(aumilieux, creerCommandBras(45, -13)), |                 Map.entry(aumilieux, creerCommandBras(9, -14)), | ||||||
|                 Map.entry(enbas, creerCommandBras(12, -9)), |                 Map.entry(enbas, creerCommandBras(44, -17)), | ||||||
|                 Map.entry(nulpart, creerCommandBras(0, 0))), chooser::getSelected), |                 Map.entry(nulpart, creerCommandBras(0, 0))), chooser::getSelected), | ||||||
|             new OuvrePince(pince).unless(() -> chooser.getSelected().equals(nulpart)), |             new OuvrePince(pince).unless(() -> chooser.getSelected().equals(nulpart)), | ||||||
|             Commands.waitSeconds(1), |             Commands.waitSeconds(1), | ||||||
| @@ -155,8 +156,8 @@ public class RobotContainer { | |||||||
|             Commands.waitSeconds(1), |             Commands.waitSeconds(1), | ||||||
|             Commands.either(reculers, reculerb, () -> autosortir.getBoolean(true)), |             Commands.either(reculers, reculerb, () -> autosortir.getBoolean(true)), | ||||||
|             new Avancer(basePilotable, () -> avancerdistance.getDouble(0)).unless(() -> !autosortir.getBoolean(true) || !autobalance.getBoolean(false)), |             new Avancer(basePilotable, () -> avancerdistance.getDouble(0)).unless(() -> !autosortir.getBoolean(true) || !autobalance.getBoolean(false)), | ||||||
|             Commands.either(new Gyro(basePilotable), Commands.none(), () -> autobalance.getBoolean(true)))) |             Commands.either(gyro, Commands.none(), () -> autobalance.getBoolean(true)))) | ||||||
|         .andThen(new BrakeOuvre(basePilotable)); |         .andThen(brakeOuvre); | ||||||
|  |  | ||||||
|   } |   } | ||||||
| } | } | ||||||
|   | |||||||
| @@ -32,7 +32,7 @@ public class Apriltag extends CommandBase { | |||||||
|   // 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() { | ||||||
|     basePilotable.drive(doubleSupplier.getAsDouble(), limelight.getYaw()); |     basePilotable.drive(doubleSupplier.getAsDouble(), limelight.getYaw(),false); | ||||||
|   } |   } | ||||||
|  |  | ||||||
|   // Called once the command ends or is interrupted. |   // Called once the command ends or is interrupted. | ||||||
|   | |||||||
| @@ -5,6 +5,7 @@ | |||||||
| package frc.robot.commands; | package frc.robot.commands; | ||||||
|  |  | ||||||
|  |  | ||||||
|  |  | ||||||
| import edu.wpi.first.wpilibj2.command.CommandBase; | import edu.wpi.first.wpilibj2.command.CommandBase; | ||||||
| import frc.robot.subsystems.Gratte; | import frc.robot.subsystems.Gratte; | ||||||
|  |  | ||||||
|   | |||||||
| @@ -4,6 +4,7 @@ | |||||||
|  |  | ||||||
| package frc.robot.commands; | package frc.robot.commands; | ||||||
|  |  | ||||||
|  |  | ||||||
| import edu.wpi.first.wpilibj2.command.CommandBase; | import edu.wpi.first.wpilibj2.command.CommandBase; | ||||||
| import frc.robot.subsystems.BasePilotable; | import frc.robot.subsystems.BasePilotable; | ||||||
|  |  | ||||||
|   | |||||||
| @@ -32,7 +32,7 @@ public class Tape extends CommandBase { | |||||||
|   // 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() { | ||||||
|     basePilotable.drive(doubleSupplier.getAsDouble(), limelight.getYaw()); |     basePilotable.drive(doubleSupplier.getAsDouble(), limelight.getYaw(),false); | ||||||
|   } |   } | ||||||
|  |  | ||||||
|   // Called once the command ends or is interrupted. |   // Called once the command ends or is interrupted. | ||||||
|   | |||||||
| @@ -18,6 +18,7 @@ import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; | |||||||
| import edu.wpi.first.wpilibj2.command.SubsystemBase; | import edu.wpi.first.wpilibj2.command.SubsystemBase; | ||||||
| import frc.robot.Constants; | import frc.robot.Constants; | ||||||
|  |  | ||||||
|  |  | ||||||
| public class BasePilotable extends SubsystemBase { | public class BasePilotable extends SubsystemBase { | ||||||
|   final CANSparkMax avantdroit = new CANSparkMax(Constants.avantdroit, MotorType.kBrushless); |   final CANSparkMax avantdroit = new CANSparkMax(Constants.avantdroit, MotorType.kBrushless); | ||||||
|   final CANSparkMax avantgauche = new CANSparkMax(Constants.avantgauche, MotorType.kBrushless); |   final CANSparkMax avantgauche = new CANSparkMax(Constants.avantgauche, MotorType.kBrushless); | ||||||
| @@ -42,6 +43,9 @@ public class BasePilotable extends SubsystemBase { | |||||||
|   public void drive(double xSpeed, double zRotation){ |   public void drive(double xSpeed, double zRotation){ | ||||||
|     drive.arcadeDrive(xSpeed, zRotation); |     drive.arcadeDrive(xSpeed, zRotation); | ||||||
|   } |   } | ||||||
|  |   public void drive(double xSpeed, double zRotation, boolean square){ | ||||||
|  |     drive.arcadeDrive(xSpeed, zRotation, square); | ||||||
|  |   } | ||||||
|   public double distance(){ |   public double distance(){ | ||||||
|     return (-avantdroit.getEncoder().getPosition() |     return (-avantdroit.getEncoder().getPosition() | ||||||
|     +avantgauche.getEncoder().getPosition() |     +avantgauche.getEncoder().getPosition() | ||||||
|   | |||||||
| @@ -41,12 +41,13 @@ public class Limelight extends SubsystemBase { | |||||||
|   public void tape() { |   public void tape() { | ||||||
|     limelight.setLED(VisionLEDMode.kOn); |     limelight.setLED(VisionLEDMode.kOn); | ||||||
|     limelight.setPipelineIndex(1); |     limelight.setPipelineIndex(1); | ||||||
|  |  | ||||||
|   } |   } | ||||||
|  |  | ||||||
|   public double getYaw() { |   public double getYaw() { | ||||||
|     var result = limelight.getLatestResult(); |     var result = limelight.getLatestResult(); | ||||||
|     if(result.hasTargets()){ |     if(result.hasTargets()){ | ||||||
|     return   -result.getBestTarget().getYaw()/30; |     return   -result.getBestTarget().getYaw()/45; | ||||||
|     } |     } | ||||||
|     return 0; |     return 0; | ||||||
|    |    | ||||||
|   | |||||||
		Reference in New Issue
	
	Block a user